diff --git a/.env b/.env
index 5298a5ae5..23b50c4f0 100644
--- a/.env
+++ b/.env
@@ -30,28 +30,26 @@ ROBOT_LAUNCH_PACKAGE="robot_bringup"
ROBOT_LAUNCH_FILE="robot.launch.xml"
# See robot-base-docker-compose.yaml for how these variables get propagated.
-# We use relative launch path (not file) because these are launch files get included
-# from the top level robot launch file, and the include-format requires a path.
AUTONOMY_LAUNCH_PACKAGE="autonomy_bringup"
-AUTONOMY_LAUNCH_PATH="launch/autonomy.launch.xml"
+AUTONOMY_LAUNCH_FILE="autonomy.launch.xml"
# --
INTERFACE_LAUNCH_PACKAGE="interface_bringup"
-INTERFACE_LAUNCH_PATH="launch/interface.launch.xml"
+INTERFACE_LAUNCH_FILE="interface.launch.xml"
# --
SENSORS_LAUNCH_PACKAGE="sensors_bringup"
-SENSORS_LAUNCH_PATH="launch/sensors.launch.xml"
+SENSORS_LAUNCH_FILE="sensors.launch.xml"
# --
PERCEPTION_LAUNCH_PACKAGE="perception_bringup"
-PERCEPTION_LAUNCH_PATH="launch/perception.launch.xml"
+PERCEPTION_LAUNCH_FILE="perception.launch.xml"
# --
LOCAL_LAUNCH_PACKAGE="local_bringup"
-LOCAL_LAUNCH_PATH="launch/local.launch.xml"
+LOCAL_LAUNCH_FILE="local.launch.xml"
# --
GLOBAL_LAUNCH_PACKAGE="global_bringup"
-GLOBAL_LAUNCH_PATH="launch/global.launch.xml"
+GLOBAL_LAUNCH_FILE="global.launch.xml"
# --
BEHAVIOR_LAUNCH_PACKAGE="behavior_bringup"
-BEHAVIOR_LAUNCH_PATH="launch/behavior.launch.xml"
+BEHAVIOR_LAUNCH_FILE="behavior.launch.xml"
# ===============================================
# =========== GROUND CONTROL STATION ============
diff --git a/robot/docker/robot-base-docker-compose.yaml b/robot/docker/robot-base-docker-compose.yaml
index 22775ea54..f2e394261 100644
--- a/robot/docker/robot-base-docker-compose.yaml
+++ b/robot/docker/robot-base-docker-compose.yaml
@@ -12,25 +12,25 @@ services:
- QT_X11_NO_MITSHM=1
# docker compose interpolation to env variables
- AUTONOMY_LAUNCH_PACKAGE=${AUTONOMY_LAUNCH_PACKAGE}
- - AUTONOMY_LAUNCH_PATH=${AUTONOMY_LAUNCH_PATH}
+ - AUTONOMY_LAUNCH_FILE=${AUTONOMY_LAUNCH_FILE}
# --
- INTERFACE_LAUNCH_PACKAGE=${INTERFACE_LAUNCH_PACKAGE}
- - INTERFACE_LAUNCH_PATH=${INTERFACE_LAUNCH_PATH}
+ - INTERFACE_LAUNCH_FILE=${INTERFACE_LAUNCH_FILE}
# --
- SENSORS_LAUNCH_PACKAGE=${SENSORS_LAUNCH_PACKAGE}
- - SENSORS_LAUNCH_PATH=${SENSORS_LAUNCH_PATH}
+ - SENSORS_LAUNCH_FILE=${SENSORS_LAUNCH_FILE}
# --
- PERCEPTION_LAUNCH_PACKAGE=${PERCEPTION_LAUNCH_PACKAGE}
- - PERCEPTION_LAUNCH_PATH=${PERCEPTION_LAUNCH_PATH}
+ - PERCEPTION_LAUNCH_FILE=${PERCEPTION_LAUNCH_FILE}
# --
- LOCAL_LAUNCH_PACKAGE=${LOCAL_LAUNCH_PACKAGE}
- - LOCAL_LAUNCH_PATH=${LOCAL_LAUNCH_PATH}
+ - LOCAL_LAUNCH_FILE=${LOCAL_LAUNCH_FILE}
# --
- GLOBAL_LAUNCH_PACKAGE=${GLOBAL_LAUNCH_PACKAGE}
- - GLOBAL_LAUNCH_PATH=${GLOBAL_LAUNCH_PATH}
+ - GLOBAL_LAUNCH_FILE=${GLOBAL_LAUNCH_FILE}
# --
- BEHAVIOR_LAUNCH_PACKAGE=${BEHAVIOR_LAUNCH_PACKAGE}
- - BEHAVIOR_LAUNCH_PATH=${BEHAVIOR_LAUNCH_PATH}
+ - BEHAVIOR_LAUNCH_FILE=${BEHAVIOR_LAUNCH_FILE}
deploy:
# let it use the GPU
resources:
@@ -38,7 +38,7 @@ services:
devices:
- driver: nvidia # https://stackoverflow.com/a/70761193
count: 1
- capabilities: [ gpu ]
+ capabilities: [gpu]
volumes:
# display stuff
- $HOME/.Xauthority:/root/.Xauthority
@@ -49,7 +49,7 @@ services:
- /var/run/docker.sock:/var/run/docker.sock # access docker API for container name
- ../../common/inputrc:/etc/inputrc:rw # for using page up/down to search through command history
# autonomy stack stuff
- - ../../common/ros_packages:/root/ros_ws/src/common:rw # common ROS packages
- - ../../common/ros_packages/fastdds.xml:/root/ros_ws/fastdds.xml:rw # fastdds.xml
- - ../ros_ws:/root/ros_ws:rw # robot-specific ROS packages
+ - ../../common/ros_packages:/root/ros_ws/src/common:rw # common ROS packages
+ - ../../common/ros_packages/fastdds.xml:/root/ros_ws/fastdds.xml:rw # fastdds.xml
+ - ../ros_ws:/root/ros_ws:rw # robot-specific ROS packages
diff --git a/robot/ros_ws/src/autonomy/0_interface/interface_bringup/launch/interface.launch.xml b/robot/ros_ws/src/autonomy/0_interface/interface_bringup/launch/interface.launch.xml
index dc3a6513f..50d87e642 100644
--- a/robot/ros_ws/src/autonomy/0_interface/interface_bringup/launch/interface.launch.xml
+++ b/robot/ros_ws/src/autonomy/0_interface/interface_bringup/launch/interface.launch.xml
@@ -1,15 +1,9 @@
+
-
-
-
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
+
+
+
+
+
+
+
-
+
-
+
-
+
-
-
-
-
-
-
-
-
-
-
+ namespace="drone_safety_monitor"
+ output="screen">
+
+
+
-
-
+
+
\ No newline at end of file
diff --git a/robot/ros_ws/src/autonomy/0_interface/robot_interface/src/odometry_conversion.cpp b/robot/ros_ws/src/autonomy/0_interface/robot_interface/src/odometry_conversion.cpp
index 8f17ca41f..c5d43daaf 100644
--- a/robot/ros_ws/src/autonomy/0_interface/robot_interface/src/odometry_conversion.cpp
+++ b/robot/ros_ws/src/autonomy/0_interface/robot_interface/src/odometry_conversion.cpp
@@ -26,8 +26,8 @@
/**
* @brief
* Does several things
- * - if there's an odometry, republishes it with a new frame_id
- * - if there's an odometry, republishes it as a transform
+ * - if the input odometry is in a different frame, either transform it or overwrite it to new frame_id
+ * - if there's an input odometry, republishes into the tf2 transform tree
* - converts MAVROS odometry BEST_EFFORT to RELIABLE
*
*/
diff --git a/robot/ros_ws/src/autonomy/1_sensors/camera_param_server/config/camera_config.yaml b/robot/ros_ws/src/autonomy/1_sensors/camera_param_server/config/camera_config.yaml
index 629c4e9e7..1949eb042 100644
--- a/robot/ros_ws/src/autonomy/1_sensors/camera_param_server/config/camera_config.yaml
+++ b/robot/ros_ws/src/autonomy/1_sensors/camera_param_server/config/camera_config.yaml
@@ -3,5 +3,5 @@ camera_list:
- camera_name: "front_stereo"
camera_type: "stereo"
camera_info_sub_topic: "camera_info"
- left_camera_frame_id: "left_camera" # not sure if this is needed because it should be standardized
- right_camera_frame_id: "right_camera"
+ left_camera_frame_id: "CameraLeft"
+ right_camera_frame_id: "CameraRight"
diff --git a/robot/ros_ws/src/autonomy/2_perception/MAC-VO-ROS/config/interface_config.yaml b/robot/ros_ws/src/autonomy/2_perception/MAC-VO-ROS/config/interface_config.yaml
index 415e7fb20..e5460f47b 100644
--- a/robot/ros_ws/src/autonomy/2_perception/MAC-VO-ROS/config/interface_config.yaml
+++ b/robot/ros_ws/src/autonomy/2_perception/MAC-VO-ROS/config/interface_config.yaml
@@ -2,8 +2,7 @@
ros__parameters:
camera_name: "front_stereo"
camera_param_server_client_topic: "sensors/get_camera_params"
- # coordinate_frame: "robot_origin_ned"
- coordinate_frame: "map_ned"
+ coordinate_frame: "macvo_ned"
imageL_sub_topic: "left/image_rect"
imageR_sub_topic: "right/image_rect"
pose_pub_topic: "pose"
diff --git a/robot/ros_ws/src/autonomy/2_perception/MAC-VO-ROS/macvo/macvo.py b/robot/ros_ws/src/autonomy/2_perception/MAC-VO-ROS/macvo/macvo.py
index d29819246..80b0db738 100644
--- a/robot/ros_ws/src/autonomy/2_perception/MAC-VO-ROS/macvo/macvo.py
+++ b/robot/ros_ws/src/autonomy/2_perception/MAC-VO-ROS/macvo/macvo.py
@@ -40,14 +40,14 @@
class macvoNode(Node):
def __init__(self) -> None:
super().__init__("macvo_node")
- self.coord_frame = "map_ned" # FIXME: this is probably wrong? Should be the camera optical center frame
+ self.coord_frame = "macvo_ned" # Coordinate frame for the camera, in NED (North-East-Down) convention
self.frame_id = 0 # Frame ID
self.init_time = None # ROS2 time stamp
self.get_logger().set_level(logging.INFO)
self.get_logger().info(f"{os.getcwd()}")
self.declared_parameters = set()
- self.coord_frame = self.get_string_param("coordinate_frame") # FIXME: this is probably wrong? Should be the camera optical center frame
+ self.coord_frame = self.get_string_param("coordinate_frame")
self.frame_id = 0 # Frame ID
# Load the Camera model ------------------------------------
diff --git a/robot/ros_ws/src/autonomy/2_perception/perception_bringup/launch/perception.launch.xml b/robot/ros_ws/src/autonomy/2_perception/perception_bringup/launch/perception.launch.xml
index 1ba89b33d..e9df5ce6b 100644
--- a/robot/ros_ws/src/autonomy/2_perception/perception_bringup/launch/perception.launch.xml
+++ b/robot/ros_ws/src/autonomy/2_perception/perception_bringup/launch/perception.launch.xml
@@ -1,8 +1,19 @@
+
+
+
+
+
+
+
@@ -11,4 +22,5 @@
+
\ No newline at end of file
diff --git a/robot/ros_ws/src/autonomy/2_perception/perception_bringup/launch/perception_no_macvo.launch.xml b/robot/ros_ws/src/autonomy/2_perception/perception_bringup/launch/perception_no_macvo.launch.xml
deleted file mode 100644
index 7040dc439..000000000
--- a/robot/ros_ws/src/autonomy/2_perception/perception_bringup/launch/perception_no_macvo.launch.xml
+++ /dev/null
@@ -1,20 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/robot/ros_ws/src/autonomy/3_local/a_world_models/disparity_expansion/config/disparity_expansion_params.yaml b/robot/ros_ws/src/autonomy/3_local/a_world_models/disparity_expansion/config/disparity_expansion_params.yaml
index 6443a3dbf..f7dba5ca2 100644
--- a/robot/ros_ws/src/autonomy/3_local/a_world_models/disparity_expansion/config/disparity_expansion_params.yaml
+++ b/robot/ros_ws/src/autonomy/3_local/a_world_models/disparity_expansion/config/disparity_expansion_params.yaml
@@ -4,7 +4,6 @@
metric_depth_scale: 1.0 # units size of a meter. depth value corresponds to this many meters
downsample_scale: 0.5 # the ratio to scale down the disparity image before processing. DROAN expects 960x600. So if the incoming image is 480x300, set this to 0.5 so that it scales up
baseline_fallback: 0.12 # if the baseline is 0 from the camera_info, use this value instead
- lut_max_disparity: 180 # maximum disparity value in the disparity image
# expansion_radius: 0.325 # 0.325 is the spirit drone blade to blade
expansion_radius: 0.1 # debug hack to make disparity expansion not crash
bg_multiplier: 1.0
diff --git a/robot/ros_ws/src/autonomy/3_local/a_world_models/disparity_expansion/src/disparity_expansion.cpp b/robot/ros_ws/src/autonomy/3_local/a_world_models/disparity_expansion/src/disparity_expansion.cpp
index dcfb92cd0..64652737d 100644
--- a/robot/ros_ws/src/autonomy/3_local/a_world_models/disparity_expansion/src/disparity_expansion.cpp
+++ b/robot/ros_ws/src/autonomy/3_local/a_world_models/disparity_expansion/src/disparity_expansion.cpp
@@ -27,9 +27,6 @@ DisparityExpansionNode::DisparityExpansionNode(const rclcpp::NodeOptions& option
this->get_parameter("metric_depth_scale", this->metric_depth_scale);
this->declare_parameter("expansion_radius", 2.0);
this->get_parameter("expansion_radius", this->expansion_radius);
- this->declare_parameter("lut_max_disparity", 164);
- this->get_parameter("lut_max_disparity", this->lut_max_disparity);
- table_d.resize(this->lut_max_disparity, 0.0);
this->declare_parameter("padding", 2.0);
this->get_parameter("padding", this->padding);
this->declare_parameter("baseline_fallback", 0.5);
@@ -45,9 +42,9 @@ DisparityExpansionNode::DisparityExpansionNode(const rclcpp::NodeOptions& option
"camera_info", 1,
std::bind(&DisparityExpansionNode::set_cam_info, this, std::placeholders::_1));
- this->disparity_sub_ = this->create_subscription(
- "disparity", 1,
- std::bind(&DisparityExpansionNode::process_disparity_image, this, std::placeholders::_1));
+ // this->disparity_sub_ = this->create_subscription(
+ // "disparity", 1,
+ // std::bind(&DisparityExpansionNode::process_disparity_image, this, std::placeholders::_1));
this->depth_sub_ = this->create_subscription(
"depth", 1,
@@ -102,10 +99,12 @@ void DisparityExpansionNode::generate_expansion_lookup_table() {
RCLCPP_INFO(this->get_logger(), "Fx Fy Cx Cy: %f %f , %f %f \nW H this->baseline: %d %d %f",
this->fx, this->fy, this->cx, this->cy, this->width, this->height, this->baseline);
double r = this->expansion_radius; // expansion radius in cm
+ this->lut_max_disparity = (int) std::ceil(this->baseline * this->fx * this->metric_depth_scale);
this->table_u = std::vector>(this->lut_max_disparity,
std::vector(this->width));
this->table_v = std::vector>(this->lut_max_disparity,
std::vector(this->height));
+ this->table_d.resize(this->lut_max_disparity, 0.0);
int u1, u2, v1, v2;
double x, y, z;
double disparity;
@@ -116,7 +115,7 @@ void DisparityExpansionNode::generate_expansion_lookup_table() {
z = this->baseline * this->fx / disparity;
double disp_new = this->baseline * this->fx / (z - this->expansion_radius) + 0.5;
- table_d.at(disp_idx) = disp_new;
+ this->table_d.at(disp_idx) = disp_new;
for (int v = (int)height - 1; v >= 0; --v) {
y = (v - this->cy) * z / this->fy;
@@ -196,6 +195,7 @@ void DisparityExpansionNode::process_depth_image(
}
cv::Mat disparity_image = this->convert_depth_to_disparity(cv_ptr->image);
+
auto disparity_msg = std::make_shared();
disparity_msg->header = msg->header;
disparity_msg->image =
@@ -222,9 +222,6 @@ cv::Mat DisparityExpansionNode::convert_depth_to_disparity(const cv::Mat& depth_
RCLCPP_INFO_ONCE(this->get_logger(), "Baseline: %.4f", this->baseline);
RCLCPP_INFO_ONCE(this->get_logger(), "Focal length (fx): %.4f", this->fx);
- cv::patchNaNs(disparity_image, 0.0f);
-
- disparity_image.setTo(0.0f, disparity_image == std::numeric_limits::infinity());
return disparity_image;
}
@@ -247,6 +244,7 @@ void DisparityExpansionNode::process_disparity_image(
img_msg->step = msg_disp->image.step;
img_msg->data = msg_disp->image.data;
+
cv_bridge::CvImagePtr fg_msg(new cv_bridge::CvImage());
cv_bridge::CvImagePtr bg_msg(new cv_bridge::CvImage());
@@ -269,6 +267,7 @@ void DisparityExpansionNode::process_disparity_image(
return;
}
+
cv::Mat disparity_fg;
cv::Mat disparity_bg;
cv::Mat disparity32F_bg;
@@ -328,6 +327,10 @@ void DisparityExpansionNode::process_disparity_image(
cv::Rect roi = cv::Rect(u1, v, (u2 - u1), 1);
cv::Mat submat_t = disparity32F(roi).clone();
+ if (submat_t.empty()) {
+ RCLCPP_ERROR(this->get_logger(), "submat_t is empty for roi: %s", roi);
+ continue;
+ }
double min, max;
cv::Point p1, p2;
@@ -409,6 +412,10 @@ void DisparityExpansionNode::process_disparity_image(
cv::Rect roi = cv::Rect(u, v1, 1, (v2 - v1));
cv::Mat submat_t = disparity32F_bg(roi).clone();
+ if (submat_t.empty()) {
+ RCLCPP_ERROR(this->get_logger(), "submat_t is empty for roi: %s", roi);
+ continue;
+ }
double min, max;
cv::Point p1, p2;
diff --git a/robot/ros_ws/src/autonomy/3_local/local_bringup/launch/local.launch.xml b/robot/ros_ws/src/autonomy/3_local/local_bringup/launch/local.launch.xml
index 3ae07513f..47a1c8cf1 100644
--- a/robot/ros_ws/src/autonomy/3_local/local_bringup/launch/local.launch.xml
+++ b/robot/ros_ws/src/autonomy/3_local/local_bringup/launch/local.launch.xml
@@ -1,5 +1,10 @@
+
+
+
+
+
@@ -21,15 +26,15 @@
to="/$(env ROBOT_NAME)/trajectory_controller/trajectory_completion_percentage" />
-
-
+
+
+ args="--log-level DEBUG">
@@ -37,27 +42,25 @@
-
+
-
+
-
+
-
-
-
-
@@ -75,13 +78,12 @@
-
+
-
+
-
@@ -141,7 +143,7 @@
-
+
@@ -153,4 +155,4 @@
output="screen" respawn="true" respawn_delay="1" />
?>
-
+
\ No newline at end of file
diff --git a/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy.launch.xml b/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy.launch.xml
index 88cfb088e..75edf5bdc 100644
--- a/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy.launch.xml
+++ b/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy.launch.xml
@@ -1,22 +1,27 @@
+
+
-
+
-
+
-
+
-
+
-
+
-
+
\ No newline at end of file
diff --git a/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy_gps_groundtruth_depth.launch.xml b/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy_gps_groundtruth_depth.launch.xml
new file mode 100644
index 000000000..a241375de
--- /dev/null
+++ b/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy_gps_groundtruth_depth.launch.xml
@@ -0,0 +1,33 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy_macvo_obstacle_avoidance.launch.xml b/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy_macvo_obstacle_avoidance.launch.xml
new file mode 100644
index 000000000..c41b36bbc
--- /dev/null
+++ b/robot/ros_ws/src/autonomy/autonomy_bringup/launch/autonomy_macvo_obstacle_avoidance.launch.xml
@@ -0,0 +1,34 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/robot/ros_ws/src/robot_bringup/launch/robot.launch.xml b/robot/ros_ws/src/robot_bringup/launch/robot.launch.xml
index b76d1727d..e6c538cae 100644
--- a/robot/ros_ws/src/robot_bringup/launch/robot.launch.xml
+++ b/robot/ros_ws/src/robot_bringup/launch/robot.launch.xml
@@ -2,7 +2,7 @@
-
+
@@ -11,14 +11,14 @@
-
+ args="-d $(find-pkg-share robot_bringup)/rviz/robot.rviz --ros-args --log-level INFO"
+ output="screen" respawn="true" respawn_delay="1" />
+
+ args="--perspective-file $(find-pkg-share robot_bringup)/config/core.perspective">
+ to="/$(env ROBOT_NAME)/fixed_trajectory_generator/fixed_trajectory_command" />
@@ -28,16 +28,17 @@
-
+
-
-
+
@@ -47,4 +48,4 @@
args="/root/ros_ws/src/robot_bringup/params/domain_bridge.yaml"
output="screen" respawn="true" respawn_delay="1" />
-
+
\ No newline at end of file
diff --git a/robot/ros_ws/src/robot_bringup/launch/static_transforms.launch.xml b/robot/ros_ws/src/robot_bringup/launch/static_transforms.launch.xml
index 0a2da8b2e..d0fe422d7 100644
--- a/robot/ros_ws/src/robot_bringup/launch/static_transforms.launch.xml
+++ b/robot/ros_ws/src/robot_bringup/launch/static_transforms.launch.xml
@@ -9,5 +9,6 @@
args="0 0 0 0 0 0 mavros_enu map" />
+
diff --git a/robot/ros_ws/src/robot_bringup/rviz/robot.rviz b/robot/ros_ws/src/robot_bringup/rviz/robot.rviz
index 642320960..acacb6fbf 100644
--- a/robot/ros_ws/src/robot_bringup/rviz/robot.rviz
+++ b/robot/ros_ws/src/robot_bringup/rviz/robot.rviz
@@ -5,12 +5,14 @@ Panels:
Property Tree Widget:
Expanded:
- /Global Options1
+ - /TF1
- /TF1/Frames1
- /Sensors1
- /Perception1
- /Perception1/MACVO PointCloud1
- /Local1
- /Local1/DROAN1/Trimmed Global Plan for DROAN1/Topic1
+ - /Global1
Splitter Ratio: 0.590062141418457
Tree Height: 704
- Class: rviz_common/Selection
@@ -30,7 +32,7 @@ Panels:
Experimental: false
Name: Time
SyncMode: 0
- SyncSource: Lidar
+ SyncSource: MACVO PointCloud
Visualization Manager:
Class: ""
Displays:
@@ -57,6 +59,12 @@ Visualization Manager:
Frame Timeout: 15
Frames:
All Enabled: false
+ CameraLeft:
+ Value: true
+ CameraRight:
+ Value: true
+ ZED_X:
+ Value: false
base_link:
Value: true
base_link_frd:
@@ -65,31 +73,19 @@ Visualization Manager:
Value: false
base_link_stabilized:
Value: false
- front_stereo:
+ macvo_ned:
Value: true
- left_camera:
- Value: true
- look_ahead_point:
- Value: false
- look_ahead_point_stabilized:
- Value: false
map:
Value: true
map_ned:
Value: false
mavros_enu:
- Value: true
+ Value: false
odom:
Value: false
odom_ned:
Value: false
ouster:
- Value: true
- right_camera:
- Value: true
- tracking_point:
- Value: true
- tracking_point_stabilized:
Value: false
world:
Value: true
@@ -105,27 +101,20 @@ Visualization Manager:
{}
map:
base_link:
+ ZED_X:
+ CameraLeft:
+ macvo_ned:
+ {}
+ CameraRight:
+ {}
base_link_frd:
{}
- front_stereo:
- left_camera:
- {}
- right_camera:
- {}
ouster:
{}
base_link_stabilized:
{}
- look_ahead_point:
- {}
- look_ahead_point_stabilized:
- {}
map_ned:
{}
- tracking_point:
- {}
- tracking_point_stabilized:
- {}
Update Interval: 0
Value: true
- Class: rviz_common/Group
@@ -477,15 +466,15 @@ Visualization Manager:
Value: false
Enabled: true
Name: Trajectory Controller
- Enabled: false
+ Enabled: true
Name: Local
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/Marker
- Enabled: false
+ Enabled: true
Name: VDB Mapping Marker
Namespaces:
- {}
+ "": true
Topic:
Depth: 5
Durability Policy: Volatile
@@ -493,7 +482,7 @@ Visualization Manager:
History Policy: Keep Last
Reliability Policy: Reliable
Value: vdb_mapping/vdb_map_visualization
- Value: false
+ Value: true
- Alpha: 1
Buffer Length: 1
Class: rviz_default_plugins/Path
@@ -570,25 +559,25 @@ Visualization Manager:
Views:
Current:
Class: rviz_default_plugins/Orbit
- Distance: 36.6747932434082
+ Distance: 15.65699577331543
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
- X: 0.8583331108093262
- Y: 9.488014221191406
- Z: -3.2465572357177734
+ X: 0.4246240556240082
+ Y: 1.604090690612793
+ Z: -0.884032666683197
Focal Shape Fixed Size: false
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
- Pitch: 0.2703983187675476
+ Pitch: 0.6303980350494385
Target Frame: base_link
Value: Orbit (rviz)
- Yaw: 2.9104061126708984
+ Yaw: 3.9404115676879883
Saved: ~
Window Geometry:
Displays:
diff --git a/simulation/isaac-sim/docker/user_TEMPLATE.config.json b/simulation/isaac-sim/docker/user_TEMPLATE.config.json
index 5addac523..53ad68ccc 100644
--- a/simulation/isaac-sim/docker/user_TEMPLATE.config.json
+++ b/simulation/isaac-sim/docker/user_TEMPLATE.config.json
@@ -2,10 +2,10 @@
"persistent": {
"isaac": {
"asset_root": {
- "default": "https://airlab-storage.andrew.cmu.edu:8443/omni/web3/NVIDIA/Assets/Isaac/4.1",
+ "default": "https://airlab-storage.andrew.cmu.edu:8443/omni/web3/NVIDIA/Assets/Isaac/4.2",
"nvidia": "omniverse://localhost/NVIDIA",
- "isaac": "omniverse://localhost/NVIDIA/Assets/Isaac/4.1/Isaac",
- "cloud": "http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/4.1",
+ "isaac": "omniverse://localhost/NVIDIA/Assets/Isaac/4.2/Isaac",
+ "cloud": "http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/4.2",
"timeout": 5.0
}
},