Gazebo | Ignition | Community
Ask Your Question
0

Access Joint from Sensor Element to Detect Full LIDAR Rotation

asked 2017-05-22 11:57:02 -0600

ogunasekara gravatar image

updated 2017-05-22 13:42:26 -0600

sloretz gravatar image

I've been working on a sensor plugin for a LIDAR sensor simulation. We added a plugin element nested in a sensor element. However, we need to access a joint that is also in the model. We want to know when the LIDAR makes a full 360 degree rotation around it's rotating axis. Our sdf model is the following:

<sdf version="1.5">

<model name="RPLidar-A2">
  <!-- Give the base link a unique name -->
  <link name="base">
    <!-- added to make sure model doesn't move, should be remomved later when added to full robot-->
    <gravity>0</gravity>
    <pose>0 0 0 0 0 0</pose>
    <inertial>
      <mass>1.2</mass>
      <inertia>
        <ixx>0.001087473</ixx>
        <iyy>0.001087473</iyy>
        <izz>0.001092437</izz>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyz>0</iyz>
      </inertia>
    </inertial>


    <!-- Offset the base by half the length of the cylinder -->
    <collision name="base_collision">
      <pose>0 0 0.0097 0 0 0</pose>
      <geometry>
        <cylinder>
          <!-- Radius and length provided by Velodyne -->
          <radius>.03785</radius>
          <length>.01940</length>
        </cylinder>
      </geometry>
    </collision>

    <visual name="base_visual">
      <geometry>
        <mesh>
          <uri>model://rplidar/meshes/rplidar_base.dae</uri>
        </mesh>
      </geometry>
    </visual>
  </link>

  <!-- Give the base link a unique name -->
  <link name="top">

    <!-- See abouve about gravity--> 
    <gravity>0</gravity>

    <!-- Add a ray sensor, and give it a name -->
    <sensor type="ray" name="sensor">
      <plugin name="rplidar_sensor" filename="libsensor_plugin.so"></plugin>

      <!-- Position the ray sensor based on the specification. Also rotate
           it by 90 degrees around the X-axis so that the <horizontal> rays
           become vertical -->
      <pose>0 0 0.0107 1.5707 0 0</pose>

      <!-- Enable visualization to see the rays in the GUI -->
      <visualize>true</visualize>

      <!-- Set the update rate of the sensor -->
      <update_rate>4000</update_rate>

      <ray>
        <!-- The scan element contains the horizontal and vertical beams.
             We are leaving out the vertical beams for this tutorial. -->
        <scan>
          <!-- The horizontal beams -->
          <horizontal>
            <!-- The RPLidar has 1 beam(sample) -->
            <samples>1</samples>

            <!-- Resolution is multiplied by samples to determine number of
                 simulated beams vs interpolated beams. See:
                 http://sdformat.org/spec?ver=1.6&elem=sensor#horizontal_resolution
                 -->
            <resolution>1</resolution>

            <!-- Minimum angle in radians -->
            <min_angle>0</min_angle>

            <!-- Maximum angle in radians -->
            <max_angle>0</max_angle>
          </horizontal>
        </scan>

        <!-- Range defines characteristics of an individual beam -->
        <range>

          <!-- Minimum distance of the beam -->
          <min>0.15</min>

          <!-- Maximum distance of the beam -->
          <max>6</max>

          <!-- Linear resolution of the beam -->
          <resolution>0.0001</resolution>
        </range>
      </ray>

    </sensor>

    <pose>0 0 0.01940 0 0 0</pose>
    <inertial>
      <mass>0.1</mass>
      <inertia>
        <ixx>0.000090623</ixx>
        <iyy>0.000090623</iyy>
        <izz>0.000091036</izz>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyz>0</iyz>
      </inertia>
    </inertial>
    <!-- Vertically offset the top cylinder by the length of the bottom
        cylinder and half the length of this cylinder. -->
    <collision name="top_collision">
      <pose>0 0 0.0107 0 0 0</pose>
      <geometry>
        <cylinder>
          <!-- Radius and length provided by Velodyne -->
          <radius>0.03625</radius>
          <length>0.02140</length>
        </cylinder>
      </geometry>
    </collision>

    <visual name="top_visual">
      <geometry>
        <mesh>
          <uri>model://rplidar/meshes/rplidar_top.dae</uri>
        </mesh>
      </geometry ...
(more)
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2017-10-18 13:11:53 -0600

updated 2017-10-18 13:15:38 -0600

This tutorial gives an example of how to access the model (and its joints) via a Gazebo plugin:
http://gazebosim.org/tutorials?cat=gu...
also these two plugins provide slightly different approaches:
https://github.com/ros-simulation/gaz...
https://github.com/ros-simulation/gaz...

Your boilerplate code will look a little like this:

namespace gazebo
{
    YourPlugin::YourPlugin() {}

    YourPlugin::~YourPlugin() {}

     /// \brief Load function gets called by Gazebo when the plugin is inserted in simulation 
     /// via URDF/SDF
     /// \param[in] _model A pointer to the model that this plugin is attached to.
     /// \param[in] _sdf A pointer to the plugin's SDF element.
     void YourPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
    {
        // Store the model ptr for convenience.
        this->model_ = _model;

        // Get the name of your actuator/sensor joint from the URDF/SDF
        // Assuming:
        // <gazebo reference = "SENSORLINKNAME" />
        //     <actuatorJoint>NAMEOFJOINT</actuatorJoint>
        // </gazebo>
        //
        std::string joint_name = "";
        if ( _sdf->HasElement("actuatorJoint") ) {
            joint_name = _sdf->Get<std::string>("actuatorJoint");
        } else {
            ROS_WARN_NAMED("your_plugin", "YourPlugin missing <actuatorJoint>!!!");
        }

        // Store the actuatorjoint pointer.
        this->joint_ = this->model_->GetJoint(joint_name);

        // OTHER BOILERPLATE STUFF

        // Listen to the update event. This event is broadcast every
        // simulation iteration.
        this->update_connection_ = event::Events::ConnectWorldUpdateBegin (
        boost::bind ( &YourPlugin::OnUpdate, this, _1 ) );
    }

    // SETUP GAZEBO/ROS MESSAGING

    /// \brief Function called at each simulation interation
    void YourPlugin::OnUpdate(const common::UpdateInfo & _info)
    {
        current_joint_angle = this->joint_->GetAngle(0).Radian() // Get joint angle

        // DO COOL STUFF / PUBLISH JOINT ANGLE
    }

     // Tell Gazebo about this plugin, so that Gazebo can call Load on this plugin.
    GZ_REGISTER_MODEL_PLUGIN(YourPlugin)
}
edit flag offensive delete link more

Comments

1

This is for a ModelPlugin. Both I and the OP are implementing SensorPlugins. From the SensorPlugin there is no easy access to the Model object. I'm already using a derivative of the code from that tutorial to drive the motor, but the sensors being spun have no easy access to the angle of the motor. Use of physics::get_world() and drilling down through Model to Joint does provide that access though. I didn't quite get things working yesterday but did get access to the Joint object.

RedDave gravatar imageRedDave ( 2017-10-19 04:54:33 -0600 )edit

Whoops my bad.. Glad you found a solution!

josephcoombe gravatar imagejosephcoombe ( 2017-10-19 16:25:53 -0600 )edit

Thanks. And thanks for you original suggestions. @josephcoombe

RedDave gravatar imageRedDave ( 2017-10-20 01:44:20 -0600 )edit
0

answered 2017-10-18 10:48:58 -0600

RedDave gravatar image

Did you find a solution to this query? I have a very similar problem in that I want to access the joint's angle from the mounted sensor.

Accessing the parent of the _sdf does not seem to be the way to go. The _sdf is access to the underlying XML rather than Gazebo's objects (unless I'm wrong).

What I think we need is access to the parent model that contains the sensor for which this is the plugin. But I cannot see from the SDK how that is accessed.

Anyone have any suggestions on how to access either the World or the Model in which an element exists?

This question may have the answer: http://answers.gazebosim.org/question...

edit flag offensive delete link more

Comments

@RedDave Check out my answer - I think it answers your question too

josephcoombe gravatar imagejosephcoombe ( 2017-10-18 13:18:07 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2017-05-22 11:57:02 -0600

Seen: 1,524 times

Last updated: Oct 18 '17