Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Remote Head Support #44

Merged
merged 23 commits into from
Apr 21, 2023
Merged
Show file tree
Hide file tree
Changes from 18 commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
ccf957d
initial remote head support, mostly reconfigure updates
QuentinTorg Jun 3, 2022
02a6d91
clean up reconfigure for mono cameras and remote head
QuentinTorg Jun 3, 2022
bd03af1
reorganize the topic publishing so stereo and color topics are not ad…
QuentinTorg Jun 3, 2022
0c2cdab
add a launch file for remote head and update urdf with first pass but…
QuentinTorg Jun 3, 2022
d6cb93a
fix the urdf issues on launch caused by incorrect file paths and names
QuentinTorg Jun 3, 2022
82651ea
fix logical error in reconfigure that caused all remote heads to beha…
QuentinTorg Jun 3, 2022
da6b582
update launch files after debugging
QuentinTorg Jun 27, 2022
0fd7d96
Merge remote-tracking branch 'origin/master' into feature/remote_head…
QuentinTorg Aug 5, 2022
a9bfcac
update to latest libmultisense version
QuentinTorg Aug 5, 2022
3fa1585
Update multisense_ros/cfg/multisense.cfg
QuentinTorg Aug 5, 2022
3f41eb9
Merge remote-tracking branch 'origin/feature/remote_head_support' int…
QuentinTorg Aug 5, 2022
34679c5
update default head ID in the ros driver
QuentinTorg Aug 5, 2022
984d0cb
Add grayscale support for pointcloud colorization
mattalvarado Aug 9, 2022
9ffd4c6
account for the possibility of an uninitialized stereo calibration ma…
QuentinTorg Aug 10, 2022
3f51356
Merge remote-tracking branch 'origin/feature/remote_head_support' int…
QuentinTorg Aug 10, 2022
fab5aa3
update the valid gain range for AR0234 imagers
QuentinTorg Aug 10, 2022
21b61f8
fix typo in config
QuentinTorg Aug 10, 2022
fcd43ff
make camera.cpp robust for cameras with no right imager
QuentinTorg Aug 10, 2022
0754b96
Fix stereo_calibration_manager logic check
mattalvarado Aug 15, 2022
41f7b69
fix: changed standard to c++17 because of std::shared_mutex (#49)
Frank-Pasqualini Oct 27, 2022
5da5af6
update libmultisenes version
QuentinTorg Dec 3, 2022
4f3d300
Merge remote-tracking branch 'origin/master' into feature/remote_head…
mattalvarado Apr 21, 2023
8cc4771
Update min gain params
mattalvarado Apr 21, 2023
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
1 change: 1 addition & 0 deletions multisense_bringup/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ include_directories(include ${catkin_INCLUDE_DIRS})
install(FILES
rviz_config.rviz
multisense.launch
remote_head.launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

Expand Down
5 changes: 4 additions & 1 deletion multisense_bringup/multisense.launch
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
<launch>

<!-- Valid Sensor types are SL, S7, S7S, S21, S27, and BCAM -->
<!-- Valid Sensor types are SL, S7, S7S, S21, S27, BCAM,
remote_head_vpb, remote_head_stereo, remote_head_monocam -->

<arg name="ip_address" default="10.66.171.21" />
<arg name="namespace" default="multisense" />
<arg name="mtu" default="7200" />
<arg name="sensor" default="S21" />
<arg name="head_id" default="-1" />
mattalvarado marked this conversation as resolved.
Show resolved Hide resolved
<arg name="launch_robot_state_publisher" default="true" />
<arg name="launch_color_laser_publisher" default="false" />
<arg name="nodes_prefix" default="$(arg namespace)" />
Expand All @@ -26,6 +28,7 @@
<param name="sensor_ip" value="$(arg ip_address)" />
<param name="sensor_mtu" value="$(arg mtu)" />
<param name="tf_prefix" value="$(arg tf_prefix)" />
<param name="head_id" value="$(arg head_id)" />
</node>

<!-- Color Laser PointCloud Publisher -->
Expand Down
158 changes: 158 additions & 0 deletions multisense_bringup/remote_head.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,158 @@
<launch>

<arg name="ip_address" default="10.66.171.21" />
<arg name="mtu" default="7200" />

<arg name="launch_vpb" default="true" />
<arg name="launch_head0" default="true" />
<arg name="launch_head1" default="true" />
<arg name="launch_head2" default="true" />
<arg name="launch_head3" default="true" />

<arg name="vpb_namespace" default="multisense_vpb" />
<arg name="head0_namespace" default="remote_head_0" />
<arg name="head1_namespace" default="remote_head_1" />
<arg name="head2_namespace" default="remote_head_2" />
<arg name="head3_namespace" default="remote_head_3" />

<!-- Valid Sensor types for remote heads are remote_head_vpb, remote_head_stereo, remote_head_monocam -->
<arg name="vpb_sensor" default="remote_head_vpb" />
<arg name="head0_sensor" default="remote_head_stereo" />
<arg name="head1_sensor" default="remote_head_stereo" />
<arg name="head2_sensor" default="remote_head_stereo" />
<arg name="head3_sensor" default="remote_head_stereo" />

<arg name="vpb_nodes_prefix" default="$(arg vpb_namespace)" />
<arg name="head0_nodes_prefix" default="$(arg head0_namespace)" />
<arg name="head1_nodes_prefix" default="$(arg head1_namespace)" />
<arg name="head2_nodes_prefix" default="$(arg head2_namespace)" />
<arg name="head3_nodes_prefix" default="$(arg head3_namespace)" />

<arg name="vpb_tf_prefix" default="$(arg vpb_namespace)" />
<arg name="head0_tf_prefix" default="$(arg head0_namespace)" />
<arg name="head1_tf_prefix" default="$(arg head1_namespace)" />
<arg name="head2_tf_prefix" default="$(arg head2_namespace)" />
<arg name="head3_tf_prefix" default="$(arg head3_namespace)" />

<arg name="launch_robot_state_publisher" default="true" />

<!-- Remote Head VPB Launch-->
<group if = "$(arg launch_vpb)">

<!-- ROS Driver -->
<node pkg="multisense_ros" ns="$(arg vpb_namespace)" type="ros_driver" name="$(arg vpb_nodes_prefix)_driver" output="screen">
<param name="sensor_ip" value="$(arg ip_address)" />
<param name="sensor_mtu" value="$(arg mtu)" />
<param name="tf_prefix" value="$(arg vpb_tf_prefix)" />
<param name="head_id" value="-1" />
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why are we using a invalid default? Shouldn't we just use 0?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The -1 default makes this connect with non-remote head cameras and the VPB. 0 will be remote head ID 0

</node>

<!-- Robot state publisher -->
<group if = "$(arg launch_robot_state_publisher)">
<param name="robot_description"
command="$(find xacro)/xacro '$(find multisense_description)/urdf/multisense$(arg vpb_sensor)/standalone.urdf.xacro' name:=$(arg vpb_namespace)"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="$(arg vpb_nodes_prefix)_state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
<remap from="joint_states" to="/$(arg vpb_namespace)/joint_states" />
</node>
</group>

</group>


<!-- Remote Head 0 Launch -->
<group if = "$(arg launch_head0)">

<!-- ROS Driver -->
<node pkg="multisense_ros" ns="$(arg head0_namespace)" type="ros_driver" name="$(arg head0_nodes_prefix)_driver" output="screen">
<param name="sensor_ip" value="$(arg ip_address)" />
<param name="sensor_mtu" value="$(arg mtu)" />
<param name="tf_prefix" value="$(arg head0_tf_prefix)" />
<param name="head_id" value="0" />
</node>

<!-- Robot state publisher -->
<group if = "$(arg launch_robot_state_publisher)">
<param name="robot_description"
command="$(find xacro)/xacro '$(find multisense_description)/urdf/multisense$(arg head0_sensor)/standalone.urdf.xacro' name:=$(arg head0_namespace)"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="$(arg head0_nodes_prefix)_state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
<remap from="joint_states" to="/$(arg head0_namespace)/joint_states" />
</node>
</group>

</group>


<!-- Remote Head 1 Launch -->
<group if = "$(arg launch_head1)">

<!-- ROS Driver -->
<node pkg="multisense_ros" ns="$(arg head1_namespace)" type="ros_driver" name="$(arg head1_nodes_prefix)_driver" output="screen">
<param name="sensor_ip" value="$(arg ip_address)" />
<param name="sensor_mtu" value="$(arg mtu)" />
<param name="tf_prefix" value="$(arg head1_tf_prefix)" />
<param name="head_id" value="1" />
</node>

<!-- Robot state publisher -->
<group if = "$(arg launch_robot_state_publisher)">
<param name="robot_description"
command="$(find xacro)/xacro '$(find multisense_description)/urdf/multisense$(arg head1_sensor)/standalone.urdf.xacro' name:=$(arg head1_namespace)"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="$(arg head1_nodes_prefix)_state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
<remap from="joint_states" to="/$(arg head1_namespace)/joint_states" />
</node>
</group>

</group>


<!-- Remote Head 2 Launch -->
<group if = "$(arg launch_head2)">

<!-- ROS Driver -->
<node pkg="multisense_ros" ns="$(arg head2_namespace)" type="ros_driver" name="$(arg head2_nodes_prefix)_driver" output="screen">
<param name="sensor_ip" value="$(arg ip_address)" />
<param name="sensor_mtu" value="$(arg mtu)" />
<param name="tf_prefix" value="$(arg head2_tf_prefix)" />
<param name="head_id" value="2" />
</node>

<!-- Robot state publisher -->
<group if = "$(arg launch_robot_state_publisher)">
<param name="robot_description"
command="$(find xacro)/xacro '$(find multisense_description)/urdf/multisense$(arg head2_sensor)/standalone.urdf.xacro' name:=$(arg head2_namespace)"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="$(arg head2_nodes_prefix)_state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
<remap from="joint_states" to="/$(arg head2_namespace)/joint_states" />
</node>
</group>

</group>


<!-- Remote Head 3 Launch -->
<group if = "$(arg launch_head3)">

<!-- ROS Driver -->
<node pkg="multisense_ros" ns="$(arg head3_namespace)" type="ros_driver" name="$(arg head3_nodes_prefix)_driver" output="screen">
<param name="sensor_ip" value="$(arg ip_address)" />
<param name="sensor_mtu" value="$(arg mtu)" />
<param name="tf_prefix" value="$(arg head3_tf_prefix)" />
<param name="head_id" value="3" />
</node>

<!-- Robot state publisher -->
<group if = "$(arg launch_robot_state_publisher)">
<param name="robot_description"
command="$(find xacro)/xacro '$(find multisense_description)/urdf/multisense$(arg head3_sensor)/standalone.urdf.xacro' name:=$(arg head3_namespace)"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="$(arg head3_nodes_prefix)_state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
<remap from="joint_states" to="/$(arg head3_namespace)/joint_states" />
</node>
</group>

</group>

</launch>
86 changes: 86 additions & 0 deletions multisense_description/meshes/multisense_remote_head_monocam.STL
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
solid model
facet normal 0.0 0.0 -1.0
outer loop
vertex 20.0 0.0 0.0
vertex 0.0 -20.0 0.0
vertex 0.0 0.0 0.0
endloop
endfacet
facet normal 0.0 0.0 -1.0
outer loop
vertex 0.0 -20.0 0.0
vertex 20.0 0.0 0.0
vertex 20.0 -20.0 0.0
endloop
endfacet
facet normal -0.0 -1.0 -0.0
outer loop
vertex 20.0 -20.0 20.0
vertex 0.0 -20.0 0.0
vertex 20.0 -20.0 0.0
endloop
endfacet
facet normal -0.0 -1.0 -0.0
outer loop
vertex 0.0 -20.0 0.0
vertex 20.0 -20.0 20.0
vertex 0.0 -20.0 20.0
endloop
endfacet
facet normal 1.0 0.0 0.0
outer loop
vertex 20.0 0.0 0.0
vertex 20.0 -20.0 20.0
vertex 20.0 -20.0 0.0
endloop
endfacet
facet normal 1.0 0.0 0.0
outer loop
vertex 20.0 -20.0 20.0
vertex 20.0 0.0 0.0
vertex 20.0 0.0 20.0
endloop
endfacet
facet normal -0.0 -0.0 1.0
outer loop
vertex 20.0 -20.0 20.0
vertex 0.0 0.0 20.0
vertex 0.0 -20.0 20.0
endloop
endfacet
facet normal -0.0 -0.0 1.0
outer loop
vertex 0.0 0.0 20.0
vertex 20.0 -20.0 20.0
vertex 20.0 0.0 20.0
endloop
endfacet
facet normal -1.0 0.0 0.0
outer loop
vertex 0.0 0.0 20.0
vertex 0.0 -20.0 0.0
vertex 0.0 -20.0 20.0
endloop
endfacet
facet normal -1.0 0.0 0.0
outer loop
vertex 0.0 -20.0 0.0
vertex 0.0 0.0 20.0
vertex 0.0 0.0 0.0
endloop
endfacet
facet normal -0.0 1.0 0.0
outer loop
vertex 0.0 0.0 20.0
vertex 20.0 0.0 0.0
vertex 0.0 0.0 0.0
endloop
endfacet
facet normal -0.0 1.0 0.0
outer loop
vertex 20.0 0.0 0.0
vertex 0.0 0.0 20.0
vertex 20.0 0.0 20.0
endloop
endfacet
endsolid model
86 changes: 86 additions & 0 deletions multisense_description/meshes/multisense_remote_head_stereo.STL
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
solid model
facet normal 0.0 0.0 -1.0
outer loop
vertex 20.0 0.0 0.0
vertex 0.0 -20.0 0.0
vertex 0.0 0.0 0.0
endloop
endfacet
facet normal 0.0 0.0 -1.0
outer loop
vertex 0.0 -20.0 0.0
vertex 20.0 0.0 0.0
vertex 20.0 -20.0 0.0
endloop
endfacet
facet normal -0.0 -1.0 -0.0
outer loop
vertex 20.0 -20.0 20.0
vertex 0.0 -20.0 0.0
vertex 20.0 -20.0 0.0
endloop
endfacet
facet normal -0.0 -1.0 -0.0
outer loop
vertex 0.0 -20.0 0.0
vertex 20.0 -20.0 20.0
vertex 0.0 -20.0 20.0
endloop
endfacet
facet normal 1.0 0.0 0.0
outer loop
vertex 20.0 0.0 0.0
vertex 20.0 -20.0 20.0
vertex 20.0 -20.0 0.0
endloop
endfacet
facet normal 1.0 0.0 0.0
outer loop
vertex 20.0 -20.0 20.0
vertex 20.0 0.0 0.0
vertex 20.0 0.0 20.0
endloop
endfacet
facet normal -0.0 -0.0 1.0
outer loop
vertex 20.0 -20.0 20.0
vertex 0.0 0.0 20.0
vertex 0.0 -20.0 20.0
endloop
endfacet
facet normal -0.0 -0.0 1.0
outer loop
vertex 0.0 0.0 20.0
vertex 20.0 -20.0 20.0
vertex 20.0 0.0 20.0
endloop
endfacet
facet normal -1.0 0.0 0.0
outer loop
vertex 0.0 0.0 20.0
vertex 0.0 -20.0 0.0
vertex 0.0 -20.0 20.0
endloop
endfacet
facet normal -1.0 0.0 0.0
outer loop
vertex 0.0 -20.0 0.0
vertex 0.0 0.0 20.0
vertex 0.0 0.0 0.0
endloop
endfacet
facet normal -0.0 1.0 0.0
outer loop
vertex 0.0 0.0 20.0
vertex 20.0 0.0 0.0
vertex 0.0 0.0 0.0
endloop
endfacet
facet normal -0.0 1.0 0.0
outer loop
vertex 20.0 0.0 0.0
vertex 0.0 0.0 20.0
vertex 20.0 0.0 20.0
endloop
endfacet
endsolid model
Loading