Added odom publisher. Improved a little bit Gazebo integration
This commit is contained in:
parent
f547fd5745
commit
d89426c35a
@ -69,7 +69,7 @@
|
||||
<!-- DUMMY VALUES - CHANGE TO THE ONES YOUR CAMERAS HAVE -->
|
||||
<gazebo reference="LeftCamera">
|
||||
<sensor type="camera" name="LeftCamera">
|
||||
<update_rate>10.0</update_rate>
|
||||
<update_rate>30.0</update_rate>
|
||||
<camera name="left_camera">
|
||||
<horizontal_fov>1.06290551</horizontal_fov>
|
||||
<image>
|
||||
@ -89,7 +89,7 @@
|
||||
</camera>
|
||||
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
||||
<alwaysOn>true</alwaysOn>
|
||||
<updateRate>10.0</updateRate>
|
||||
<updateRate>30.0</updateRate>
|
||||
<cameraName>nao_dcm/CameraLeft</cameraName>
|
||||
<imageTopicName>image_raw</imageTopicName>
|
||||
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
|
||||
@ -106,7 +106,7 @@
|
||||
|
||||
<gazebo reference="RightCamera">
|
||||
<sensor type="camera" name="RightCamera">
|
||||
<update_rate>10.0</update_rate>
|
||||
<update_rate>30.0</update_rate>
|
||||
<camera name="right_camera">
|
||||
<horizontal_fov>1.06290551</horizontal_fov>
|
||||
<image>
|
||||
@ -126,7 +126,7 @@
|
||||
</camera>
|
||||
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
||||
<alwaysOn>true</alwaysOn>
|
||||
<updateRate>10.0</updateRate>
|
||||
<updateRate>30.0</updateRate>
|
||||
<cameraName>nao_dcm/CameraRight</cameraName>
|
||||
<imageTopicName>image_raw</imageTopicName>
|
||||
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
|
||||
|
@ -10,6 +10,14 @@
|
||||
<xacro:property name="use_helmet" value="true" />
|
||||
<xacro:property name="helmet_cameras_viz" value="false" />
|
||||
<xacro:property name="use_odroid" value="true" />
|
||||
<xacro:property name="use_hector_imu" value="false" />
|
||||
|
||||
<xacro:if value="${use_hector_imu}">
|
||||
<xacro:property name="imu_plugin" value="libhector_gazebo_ros_imu.so" />
|
||||
</xacro:if>
|
||||
<xacro:unless value="${use_hector_imu}">
|
||||
<xacro:property name="imu_plugin" value="libgazebo_ros_imu.so" />
|
||||
</xacro:unless>
|
||||
|
||||
<xacro:include filename="$(find nao_dcm_description)/urdf/nao_dcm_visuals_collisions.xacro" />
|
||||
<xacro:include filename="$(find nao_dcm_description)/urdf/nao_dcm_gazebo.xacro" />
|
||||
|
@ -10,6 +10,14 @@
|
||||
<xacro:property name="use_helmet" value="true" />
|
||||
<xacro:property name="helmet_cameras_viz" value="false" />
|
||||
<xacro:property name="use_odroid" value="true" />
|
||||
<xacro:property name="use_hector_imu" value="false" />
|
||||
|
||||
<xacro:if value="${use_hector_imu}">
|
||||
<xacro:property name="imu_plugin" value="libhector_gazebo_ros_imu.so" />
|
||||
</xacro:if>
|
||||
<xacro:unless value="${use_hector_imu}">
|
||||
<xacro:property name="imu_plugin" value="libgazebo_ros_imu.so" />
|
||||
</xacro:unless>
|
||||
|
||||
<xacro:include filename="$(find nao_dcm_description)/urdf/nao_dcm_visuals_collisions.xacro" />
|
||||
<xacro:include filename="$(find nao_dcm_description)/urdf/nao_dcm_gazebo.xacro" />
|
||||
|
@ -6,11 +6,15 @@
|
||||
<robotNamespace>/nao_dcm</robotNamespace>
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
</plugin>
|
||||
<plugin name="gazebo_ros_imu_controller" filename="libgazebo_ros_imu.so">
|
||||
<plugin name="gazebo_ros_imu_controller" filename="${imu_plugin}">
|
||||
<robotNamespace>/nao_dcm</robotNamespace>
|
||||
<topicName>imu_data</topicName>
|
||||
<bodyName>imu</bodyName>
|
||||
<frameId>imu</frameId>
|
||||
<gaussianNoise>2.89e-08</gaussianNoise>
|
||||
<accelGaussianNoise>2.89e-08 2.89e-08 2.89e-08</accelGaussianNoise>
|
||||
<rateGaussianNoise>2.89e-08 2.89e-08 2.89e-08</rateGaussianNoise>
|
||||
<headingGaussianNoise>2.89e-08 2.89e-08 2.89e-08</headingGaussianNoise>
|
||||
<xyzOffsets>0 0 0</xyzOffsets>
|
||||
<rpyOffsets>0 0 0</rpyOffsets>
|
||||
<updateRate>30.0</updateRate>
|
||||
|
@ -0,0 +1,24 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
|
||||
<!-- Call helper node to get rectified images from stereo system -->
|
||||
<node name="stereo_proc" pkg="stereo_image_proc" type="stereo_image_proc" respawn="false" output="screen">
|
||||
<remap from="/left/image_raw" to="/nao_dcm/CameraLeft/image_raw"/>
|
||||
<remap from="/left/camera_info" to="/nao_dcm/CameraLeft/camera_info"/>
|
||||
<remap from="/right/image_raw" to="/nao_dcm/CameraRight/image_raw"/>
|
||||
<remap from="/right/camera_info" to="/nao_dcm/CameraRight/camera_info"/>
|
||||
<param name="approximate_sync" value="True" />
|
||||
</node>
|
||||
|
||||
<!-- Call helper nodes to get visual odometry and combine it with imu data -->
|
||||
<node name="viso" pkg="viso2_ros" type="stereo_odometer" respawn="false" output="screen">
|
||||
<param name="publish_tf" value="true"/>
|
||||
<param name="approximate_sync" value="True" />
|
||||
<remap from="stereo/left/image" to="/left/image_rect"/>
|
||||
<remap from="stereo/left/camera_info" to="/nao_dcm/CameraLeft/camera_info"/>
|
||||
<remap from="stereo/right/image" to="/right/image_rect"/>
|
||||
<remap from="stereo/right/camera_info" to="/nao_dcm/CameraRight/camera_info"/>
|
||||
<remap from="/viso/odometry" to="/nao_dcm/odom"/>
|
||||
</node>
|
||||
|
||||
</launch>
|
Loading…
x
Reference in New Issue
Block a user