Robotics StackExchange | Archived questions

Error while running simple gazebo plugin

I am working with ubuntu 14.04, indigo and gazebo 2.2.6. I am trying to run the same code as in this question http://answers.gazebosim.org/question/2105/basic-joint-control-question/ but I get the following error:

gzserver: /usr/include/boost/smartptr/sharedptr.hpp:653: typename boost::detail::spmemberaccess::type boost::sharedptr::operator->() const [with T = gazebo::physics::Joint; typename boost::detail::spmember_access::type = gazebo::physics::Joint*]: Assertion `px != 0' failed.

My code is here:

 #include <boost/bind.hpp>
 #include <gazebo/gazebo.hh>
 #include <gazebo/physics/physics.hh>
 #include <gazebo/common/common.hh>
 #include <stdio.h>

 namespace gazebo
 {
  class ArmovePlugin : public ModelPlugin
 {
 public: void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/)
 {
  // Store the pointer to the model
  this->model = _parent;

 // Initialize the JointController with the model pointer
  this->j_controller = new physics::JointController(_parent);

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

 // Called by the world update start event
 public: void OnUpdate(const common::UpdateInfo & /*_info*/)
 {

  double angle(3.0);
  j_controller->SetJointPosition(this->model->GetJoint("joint1"), angle);

  }

private: physics::ModelPtr model;
private: physics::JointController * j_controller;
private: event::ConnectionPtr updateConnection;
 };

 GZ_REGISTER_MODEL_PLUGIN(ArmovePlugin)
 }

urdf:

   <?xml version="1.0"?>
   <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="armbot">
   <xacro:property name="velocity1" value="100" />
   <xacro:property name="effort1" value="1000" />
   <xacro:property name="lowerlimit" value="-1.57079" />
   <xacro:property name="upperlimit" value="1.57079" />

   <link name="world"/>

  <joint name="joint0" type="fixed">
     <parent link="world"/>
<child link="part1"/>
   </joint>

  <link name="part1">
     <visual>
       <geometry>
         <cylinder length="0.9" radius="0.05"/>
       </geometry>
       <origin rpy="0 1.57079 0" xyz="0 0 0"/>
       <material name="blackmetal">
         <color rgba="0.1 0.1 0.1 0.7"/>
  </material>
     </visual>
  <collision>
  <geometry>
     <cylinder length="0.9" radius="0.05"/>
  </geometry>
     </collision>
  <inertial>
  <origin rpy="0 1.57079 0" xyz="0 0 0"/>
  <mass value="9"/>
  <inertia ixx="0.6" ixy="0.0" ixz="0.0" iyy="0.6" iyz="0.0" izz="3.64"/>
     </inertial>
   </link>

   <link name="part2">
<visual>
  <geometry>
    <cylinder length="0.6" radius="0.05"/>
  </geometry>
  <origin rpy="0 0 0" xyz="0.45 0 0.3"/>
  <material name="blackmetal2">
    <color rgba="0.1 0.1 0.1 0.7"/>
  </material>
</visual>
  <collision>
  <geometry>
    <cylinder length="0.6" radius="0.05"/>
  </geometry>
</collision>
  <inertial>
  <origin rpy="0 0 0" xyz="0 0 0"/>
  <mass value="6"/>
  <inertia ixx="0.18" ixy="0.0" ixz="0.0" iyy="0.18" iyz="0.0" izz="1.08"/>
</inertial>
   </link>

  <joint name="joint1" type="revolute">
<parent link="part1"/>
<child link="part2"/>
<origin xyz="0.45 0 0"/>
<axis rpy="0 0 0" xyz="0 1 0" />
<calibration rising="0.0"/>
<dynamics damping="0.0" friction="0.0"/>
<limit effort="${effort1}" lower="${lowerlimit}" upper="${upperlimit}" velocity="${velocity1}"/> 
   </joint>

 <gazebo>
    <plugin name="armbot_plugin" filename="libarmbot_plugin.so">  </plugin>
 </gazebo>
 </robot>

Asked by sofia.gr on 2017-07-13 11:55:57 UTC

Comments

The first recommendation would be to upgrade to Gazebo 7, since Gazebo 2 is no longer supported.

Asked by chapulina on 2017-07-13 12:28:00 UTC

I tried Gazebo 7, and I still get the same error.

Asked by sofia.gr on 2017-07-13 14:44:34 UTC

I added the code. Does the fact that I have a urdf file cause any problem? Should I declare the plugin as world plugin? I was able to run model plugins that use PID to move the joint, but I want it to move according to the angle

Asked by sofia.gr on 2017-07-14 12:03:06 UTC

Answers