User Tools

Site Tools


neurali:gazebo_package_esempio_aggiungere_qualcosa

Aggiungere qualcosa all'esempio di package Gazebo

Aggiungere un telecomando

Modificare File.Gazebo

<gazebo>
  <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
    <alwaysOn>true</alwaysOn>
    <updateRate>100</updateRate>
    <leftJoint>left_wheel_hinge</leftJoint>
    <rightJoint>right_wheel_hinge</rightJoint>
    <wheelSeparation>${chassisWidth+wheelWidth}</wheelSeparation>
    <wheelDiameter>${2*wheelRadius}</wheelDiameter>
    <torque>20</torque>
    <commandTopic>mybot/cmd_vel</commandTopic>
    <odometryTopic>mybot/odom_diffdrive</odometryTopic>
    <odometryFrame>odom</odometryFrame>
    <robotBaseFrame>footprint</robotBaseFrame>
  </plugin>
</gazebo>

I comandi possono essere inviati con il telecomando già pronto per il turtle robot, modificando il nome del topic

rosrun turtlesim turtle_teleop_key /turtle1/cmd_vel:=/mybot/cmd_vel
rosrun turtlebot_teleop turtlebot_teleop_key /turtlebot_teleop/cmd_vel:=/mybot/cmd_vel

Aggiungere una Telecamera

Modificare file.urdf o xacro

e poi aggiungere un nuovo plugin sensore

<link name="camera">
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <box size="${cameraSize} ${cameraSize} ${cameraSize}"/>
    </geometry>
  </collision>

  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <box size="${cameraSize} ${cameraSize} ${cameraSize}"/>
    </geometry>
    <material name="blue"/>
  </visual>

  <inertial>
    <mass value="${cameraMass}" />
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <box_inertia m="${cameraMass}" x="${cameraSize}" y="${cameraSize}" z="${cameraSize}" />
  </inertial>
</link>
<gazebo reference="camera">
  <material>Gazebo/Blue</material>
  <sensor type="camera" name="camera1">
    <update_rate>30.0</update_rate>
    <camera name="head">
      <horizontal_fov>1.3962634</horizontal_fov>
      <image>
        <width>800</width>
        <height>800</height>
        <format>R8G8B8</format>
      </image>
      <clip>
        <near>0.02</near>
        <far>300</far>
      </clip>
    </camera>
    <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>0.0</updateRate>
      <cameraName>mybot/camera1</cameraName>
      <imageTopicName>image_raw</imageTopicName>
      <cameraInfoTopicName>camera_info</cameraInfoTopicName>
      <frameName>camera_link</frameName>
      <hackBaseline>0.07</hackBaseline>
      <distortionK1>0.0</distortionK1>
      <distortionK2>0.0</distortionK2>
      <distortionK3>0.0</distortionK3>
      <distortionT1>0.0</distortionT1>
      <distortionT2>0.0</distortionT2>
    </plugin>
  </sensor>
 </gazebo>

per vedere, sottoscrivo con un apposito nodo ROS

rosrun image_view image_view image:=/mybot/camera1/image_raw
neurali/gazebo_package_esempio_aggiungere_qualcosa.txt · Last modified: 2020/06/08 22:20 by 127.0.0.1