-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcarter.yaml
77 lines (77 loc) · 2.59 KB
/
carter.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
name: carter
type: sim_unreal
address: benchbot_robot:10000
global_frame: map
poses:
- robot
- initial_pose
- left_camera
- lidar
robot_frame: robot
start_cmds:
- >
sed -i "0,/\"pose\":/{s/\(\"pose\": \)\(.*\)/\1$START_POSE/}"
$ISAAC_PATH/apps/carter/carter_sim/bridge_config/carter_full_config.json &&
perl -0777 -i -pe 's/\"static_mesh\".*?\]/\"static_mesh\":$OBJECT_LABELS/s'
$ISAAC_PATH/apps/carter/carter_sim/bridge_config/carter_full_config.json &&
cd "$ENVS_PATH" &&
.sim_package/IsaacSimProject.sh "$MAP_PATH" -isaac_sim_config_json=
"$ISAAC_PATH/apps/carter/carter_sim/bridge_config/carter_full.json"
-windowed -ResX=960 -ResY=540 -vulkan -game
- >
cd "$SIM_PATH" && ./bazelros run //apps/benchbot_simulator
connections:
image_depth:
connection: "ros_to_api"
ros_topic: "/camera/depth/image_raw"
ros_type: "sensor_msgs/Image"
callback_robot: "robot_callbacks.encode_depth_image"
image_depth_info:
connection: "ros_to_api"
ros_topic: "/camera/depth/camera_info"
ros_type: "sensor_msgs/CameraInfo"
callback_robot: "robot_callbacks.encode_camera_info"
image_rgb:
connection: "ros_to_api"
ros_topic: "/camera/color/image_raw"
ros_type: "sensor_msgs/Image"
callback_api: "api_callbacks.convert_to_rgb"
callback_robot: "robot_callbacks.encode_color_image"
image_rgb_info:
connection: "ros_to_api"
ros_topic: "/camera/color/camera_info"
ros_type: "sensor_msgs/CameraInfo"
callback_robot: "robot_callbacks.encode_camera_info"
image_segment:
connection: "ros_to_api"
ros_topic: "/camera/segment/segment_msg"
ros_type: "benchbot_msgs/SegmentImages"
callback_robot: "robot_callbacks.encode_segment_image"
image_segment_info:
connection: "ros_to_api"
ros_topic: "/camera/segment/camera_info"
ros_type: "sensor_msgs/CameraInfo"
callback_robot: "robot_callbacks.encode_camera_info"
laser:
connection: "ros_to_api"
ros_topic: "/scan_laser"
ros_type: "sensor_msgs/LaserScan"
callback_robot: "robot_callbacks.encode_laserscan"
move_angle:
connection: "api_to_ros"
ros_topic: "/cmd_vel"
ros_type: "geometry_msgs/Twist"
callback_robot: "robot_callbacks.move_angle"
move_distance:
connection: "api_to_ros"
ros_topic: "/cmd_vel"
ros_type: "geometry_msgs/Twist"
callback_robot: "robot_callbacks.move_distance"
move_next:
connection: "api_to_ros"
ros_topic: "/cmd_vel"
ros_type: "geometry_msgs/Twist"
callback_robot: "robot_callbacks.move_next"
poses:
connection: "ros_to_api"
callback_robot: "robot_callbacks.create_pose_list"