ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

modelling sensors(IMU) in Gazebo

asked 2011-12-21 21:25:11 -0500

hmmm gravatar image

hi all,i need to modell sensors like:gyro,acc,magnetfieldsensor in Gazebo. Are there any examples for a sensor implemented urdf-file? how can i modell these sensors in a urdf file,for my quadrotor?

thanks, greets

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
10

answered 2011-12-22 00:53:41 -0500

DimitriProsser gravatar image

updated 2012-01-06 05:14:57 -0500

  <joint name="imu_joint" type="fixed">
    <axis xyz="1 0 0"/> <!-- 0 1 0 -->
    <origin xyz="0 0 0.19"/>
    <parent link="base_link"/>
    <child link="imu_link"/>
  </joint>


<link name="imu_link">
  <inertial>
    <mass value="0.001"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/>
  </inertial>
  <visual>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <geometry>
      <box size="0.001 0.001 0.001"/>
    </geometry>
  </visual>
  <collision>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <geometry>
      <box size=".001 .001 .001"/>
    </geometry>
  </collision>
</link>

<gazebo>
  <controller:gazebo_ros_imu name="imu_controller" plugin="libgazebo_ros_imu.so">
    <alwaysOn>true</alwaysOn>
    <updateRate>50.0</updateRate> 
    <bodyName>imu_link</bodyName>
    <topicName>imu_data</topicName>
    <gaussianNoise>2.89e-08</gaussianNoise>
    <xyzOffsets>0 0 0</xyzOffsets>
    <rpyOffsets>0 0 0</rpyOffsets>
    <interface:position name="imu_position"/>
  </controller:gazebo_ros_imu>
</gazebo>

EDIT: This publishes a topic with the type sensor_msgs/Imu. To access the data via rxplot, you could use:

rxplot /imu_data/orientation/x
edit flag offensive delete link more

Comments

hi dimitri,i edit this to my urdf,but how can i now see the imu messages? which service do i have to call?
hmmm gravatar image hmmm  ( 2012-01-05 18:40:59 -0500 )edit
rostopic echo "imu_data". It publishes to a topic with the name that you specify in `<topicName>`.
DimitriProsser gravatar image DimitriProsser  ( 2012-01-06 00:15:32 -0500 )edit
hi dimitri,thanks . i had success. But how can i plot these imu data in rxplot? it does not work.For example, i tried : rxplot imu_data/x Can you please show me the correct syntax? greetz
hmmm gravatar image hmmm  ( 2012-01-06 05:03:03 -0500 )edit

how do i use this in urdf?

rajnunes gravatar image rajnunes  ( 2016-04-14 08:37:37 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2011-12-21 21:25:11 -0500

Seen: 7,832 times

Last updated: Jan 06 '12