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

updating robot_state_publisher node and adding missing urdf configuration #8

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
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
4 changes: 2 additions & 2 deletions cvg_sim_gazebo/launch/spawn_quadrotor.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
<arg name="P" default="0"/>
<arg name="Y" default="0"/>
<!-- send the robot XML to param server -->
<param name="robot_description" command="$(find xacro)/xacro.py '$(arg model)'" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(arg model)'" />

<!-- push robot_description to factory and spawn robot in gazebo -->
<node name="spawn_robot" pkg="gazebo_ros" type="spawn_model"
Expand All @@ -26,7 +26,7 @@
respawn="false" output="screen"/>

<!-- start robot state publisher -->
<node pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher" output="screen" >
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" type="string" value="" />
</node>
Expand Down
2 changes: 1 addition & 1 deletion cvg_sim_gazebo/urdf/quadrotor.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
xmlns:xacro="http://ros.org/wiki/xacro">

<!-- Included URDF Files -->
<xacro:include filename="$(find cvg_sim_gazebo)/urdf/quadrotor_base.urdf.xacro" />
Expand Down
13 changes: 5 additions & 8 deletions cvg_sim_gazebo/urdf/quadrotor_base.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,13 +1,12 @@
<?xml version="1.0"?>

<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro"
>
<robot
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:include filename="$(find cvg_sim_gazebo_plugins)/urdf/quadrotor_plugins.urdf.xacro" />
<property name="pi" value="3.1415926535897931" />

<!-- Main quadrotor link -->
<xacro:macro name="quadrotor_base_macro">
Expand All @@ -33,8 +32,6 @@ xmlns:xacro="http://ros.org/wiki/xacro"
</collision>
</link>



<gazebo reference="base_link">
<turnGravityOff>false</turnGravityOff>
</gazebo>
Expand Down
8 changes: 2 additions & 6 deletions cvg_sim_gazebo/urdf/quadrotor_sensors.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,12 +1,8 @@
<?xml version="1.0"?>

<robot name="quadrotor_hokuyo_utm30lx"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
<robot name="quadrotor_hokuyo_utm30lx" xmlns:xacro="http://ros.org/wiki/xacro">

<property name="M_PI" value="3.1415926535897931" />
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- Included URDF Files -->
<xacro:include filename="$(find cvg_sim_gazebo)/urdf/quadrotor_base.urdf.xacro" />
Expand Down
6 changes: 3 additions & 3 deletions cvg_sim_gazebo/urdf/sensors/generic_camera.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,11 @@ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro"
>

<property name="M_PI" value="3.1415926535897931" />
<xacro:property name="M_PI" value="3.1415926535897931" />

<xacro:macro name="generic_camera" params="name sim_name parent *origin update_rate res_x res_y image_format hfov">
<joint name="${name}_joint" type="fixed">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>
Expand Down Expand Up @@ -92,7 +92,7 @@ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
<frameName>ardrone_base_${name}cam</frameName>
</plugin>
</sensor>
<turnGravityOff>true</turnGravityOff>
<turnGravityOff>false</turnGravityOff>
<material>Gazebo/Blue</material>
</gazebo>
</xacro:macro>
Expand Down
2 changes: 1 addition & 1 deletion cvg_sim_gazebo/urdf/sensors/hokuyo_utm30lx.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
>
<xacro:macro name="hokuyo_utm30lx" params="name parent *origin ros_topic update_rate ray_count min_angle max_angle">
<joint name="${name}_joint" type="fixed">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_frame"/>
</joint>
Expand Down
7 changes: 5 additions & 2 deletions cvg_sim_gazebo/urdf/sensors/sonar_sensor.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro"
>
xmlns:xacro="http://ros.org/wiki/xacro" >

<xacro:macro name="sonar_sensor" params="name parent *origin ros_topic update_rate min_range max_range field_of_view ray_count">
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
Expand Down Expand Up @@ -57,6 +57,9 @@ xmlns:xacro="http://ros.org/wiki/xacro"
</ray>

<plugin name="gazebo_ros_${name}_controller" filename="libhector_gazebo_ros_sonar.so">
<offset>0.0</offset>
<drift>0.0</drift>
<driftFrequency>0.0</driftFrequency>
<gaussianNoise>0.000</gaussianNoise>
<topicName>${ros_topic}</topicName>
<frameId>${name}_link</frameId>
Expand Down
22 changes: 20 additions & 2 deletions cvg_sim_gazebo_plugins/urdf/quadrotor_sensors.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,20 @@ xmlns:xacro="http://ros.org/wiki/xacro"
<topicName>/ardrone/imu</topicName>
<rpyOffsets>0 0 0</rpyOffsets> <!-- deprecated -->
<gaussianNoise>0</gaussianNoise> <!-- deprecated -->
<offset>0.0 0.0 0.0</offset>
<drift>0.0 0.0 0.0</drift>
<driftFrequency>0.0 0.0 0.0</driftFrequency>
<accelOffset>0 0 0</accelOffset>
<accelDrift>0.5 0.5 0.5</accelDrift>
<accelDriftFrequency>0.0 0.0 0.0</accelDriftFrequency>
<accelGaussianNoise>0.35 0.35 0.3</accelGaussianNoise>
<rateOffset>0.0 0.0 0.0</rateOffset>
<rateDrift>0.0 0.0 0.0</rateDrift>
<rateDriftFrequency>0.0 0.0 0.0</rateDriftFrequency>
<rateGaussianNoise>0.00 0.00 0.00</rateGaussianNoise>
<headingDrift>0.0</headingDrift>
<headingDriftFrequency>0.0</headingDriftFrequency>
<headingOffset>0.0</headingOffset>
<headingGaussianNoise>0.00</headingGaussianNoise>
</plugin>

Expand All @@ -35,8 +44,10 @@ xmlns:xacro="http://ros.org/wiki/xacro"
<bodyName>base_link</bodyName>
<topicName>pressure_height</topicName>
<altimeterTopicName>altimeter</altimeterTopicName>
<offset>0</offset>
<offset>0.0</offset>
<accelOffset>0</accelOffset>
<drift>0.1</drift>
<driftFrequency>0.0</driftFrequency>
<gaussianNoise>0.5</gaussianNoise>
</plugin>

Expand All @@ -45,8 +56,10 @@ xmlns:xacro="http://ros.org/wiki/xacro"
<updateRate>10.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>magnetic</topicName>
<offset>0 0 0</offset>
<offset>0.0 0.0 0.0</offset>
<accelOffset>0.0 0.0 0.0</accelOffset>
<drift>0.0 0.0 0.0</drift>
<driftFrequency>0.0 0.0 0.0</driftFrequency>
<gaussianNoise>1.3e-2 1.3e-2 1.3e-2</gaussianNoise>
</plugin>

Expand All @@ -55,10 +68,15 @@ xmlns:xacro="http://ros.org/wiki/xacro"
<updateRate>4.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>fix</topicName>
<offset>0.0 0.0 0.0</offset>
<accelOffset>0.0 0.0 0.0</accelOffset>
<velocityTopicName>fix_velocity</velocityTopicName>
<drift>5.0 5.0 5.0</drift>
<driftFrequency>0.0 0.0 0.0</driftFrequency>
<gaussianNoise>0.1 0.1 0.1</gaussianNoise>
<velocityDrift>0 0 0</velocityDrift>
<velocityOffset>0 0 0</velocityOffset>
<velocityDriftFrequency>0.0 0.0 0.0</velocityDriftFrequency>
<velocityGaussianNoise>0.1 0.1 0.1</velocityGaussianNoise>
</plugin>

Expand Down