Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,5 @@ config="big_collision_box_height:=0.5 big_collision_box_on_top:=1 big_collision_
mobilicom_shift_y:=0.01 mobilicom_shift_z:=0.2 mobilicom_yaw:=3.14152 ptuxthermo_x_offset:=0.2
ptuxthermo_y_offset:=0.18 realsense_holder_version:=5 realsense_parent_link:=omnicam_sensor_mount
realsense_roll:=0.0 realsense_shift_x:=0.0 realsense_shift_y:=0.0 realsense_shift_z:=0.0 realsense_tilt:=-1.15
realsense_upside_down:=0 realsense_yaw:=0.62831853 t265_parent_link:=rear_sensor_item top_box_j_x:=0.472"
realsense_upside_down:=0 realsense_width:=640 realsense_yaw:=0.62831853 t265_parent_link:=rear_sensor_item
top_box_j_x:=0.472"
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,13 @@
args="/model/$(arg name)/joint/front_left_flipper_j/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_left_flipper_j/cmd_pos" to="flippers_cmd_pos/front_left"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_front_left_flipper_pos_rel"
args="/model/$(arg name)/joint/front_left_flipper_j/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_left_flipper_j/cmd_pos_rel" to="flippers_cmd_pos_rel/front_left"/>
</node>

<node
pkg="ros_ign_bridge"
Expand All @@ -85,6 +92,13 @@
args="/model/$(arg name)/joint/front_right_flipper_j/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_right_flipper_j/cmd_pos" to="flippers_cmd_pos/front_right"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_front_right_flipper_pos_rel"
args="/model/$(arg name)/joint/front_right_flipper_j/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/front_right_flipper_j/cmd_pos_rel" to="flippers_cmd_pos_rel/front_right"/>
</node>

<node
pkg="ros_ign_bridge"
Expand All @@ -100,6 +114,13 @@
args="/model/$(arg name)/joint/rear_left_flipper_j/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_left_flipper_j/cmd_pos" to="flippers_cmd_pos/rear_left"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_rear_left_flipper_pos_rel"
args="/model/$(arg name)/joint/rear_left_flipper_j/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_left_flipper_j/cmd_pos_rel" to="flippers_cmd_pos_rel/rear_left"/>
</node>

<node
pkg="ros_ign_bridge"
Expand All @@ -114,7 +135,15 @@
name="ros_ign_bridge_rear_right_flipper_pos"
args="/model/$(arg name)/joint/rear_right_flipper_j/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_right_flipper_j/cmd_pos" to="flippers_cmd_pos/rear_right"/>
</node>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_rear_right_flipper_pos_rel"
args="/model/$(arg name)/joint/rear_right_flipper_j/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="/model/$(arg name)/joint/rear_right_flipper_j/cmd_pos_rel" to="flippers_cmd_pos_rel/rear_right"/>
</node>

<!-- Laser rotation control -->

<node
Expand Down
Loading