16 #include <gazebo/gazebo.hh>    17 #include <gazebo/physics/Collision.hh>    18 #include <gazebo/physics/Link.hh>    19 #include <gazebo/physics/Model.hh>    20 #include <gazebo/physics/PhysicsEngine.hh>    21 #include <gazebo/physics/Shape.hh>    22 #include <gazebo/physics/World.hh>    23 #include <gazebo/transport/TransportTypes.hh>    24 #include <gazebo/transport/transport.hh>    27 #include <geometry_msgs/Accel.h>    36 AccelerationsTestPlugin::AccelerationsTestPlugin()
    44 #if GAZEBO_MAJOR_VERSION >= 8    55   GZ_ASSERT(_model != NULL, 
"Invalid model pointer");
    56   GZ_ASSERT(_sdf != NULL, 
"Invalid SDF element pointer");
    59   this->
world = _model->GetWorld();
    62   this->
node = transport::NodePtr(
new transport::Node());
    63 #if GAZEBO_MAJOR_VERSION >= 8    69   std::string link_name;
    70   if (_sdf->HasElement(
"link_name"))
    71     link_name = _sdf->GetElement(
"link_name")->Get<std::string>();
    73   gzerr << 
"[TestPlugin] Please specify a link_name .\n";
    74   this->
link = this->
model->GetLink(link_name);
    75   if (this->
link == NULL)
    76     gzthrow(
"[TestPlugin] Could not find specified link \""    77       << link_name << 
"\".");
    85     gzerr << 
"Not loading plugin since ROS has not been "    86           << 
"properly initialized.  Try starting gazebo with ros plugin:\n"    87           << 
"  gazebo -s libgazebo_ros_api_plugin.so\n";
    94     this->
rosNode->advertise<geometry_msgs::Accel>(
"accel_w_gazebo", 10);
    96     this->
rosNode->advertise<geometry_msgs::Accel>(
"accel_w_numeric", 10);
    99     this->
rosNode->advertise<geometry_msgs::Accel>(
"accel_b_gazebo", 10);
   101     this->
rosNode->advertise<geometry_msgs::Accel>(
"accel_b_numeric", 10);
   112   geometry_msgs::Accel amsg;
   113   amsg.linear.x = acc[0];
   114   amsg.linear.y = acc[1];
   115   amsg.linear.z = acc[2];
   116   amsg.angular.x = acc[3];
   117   amsg.angular.y = acc[4];
   118   amsg.angular.z = acc[5];
   125   r << m(0, 0), m(0, 1), m(0, 2),
   126     m(1, 0), m(1, 1), m(1, 2),
   127     m(2, 0), m(2, 1), m(2, 1);
   134   double dt = (_info.simTime - 
lastTime).Double();
   137   ignition::math::Pose3d pose_w_b;
   138 #if GAZEBO_MAJOR_VERSION >= 8   139   pose_w_b = this->
link->WorldPose();
   141   pose_w_b = this->
link->GetWorldPose().Ign();
   145 #if GAZEBO_MAJOR_VERSION >= 8   148   this->
link->RelativeLinearVel(),
   149   this->
link->RelativeAngularVel());
   153   this->
link->WorldLinearVel(),
   154   this->
link->WorldAngularVel());
   159   this->
link->WorldLinearAccel(),
   160   this->
link->WorldAngularAccel());
   164   this->
link->RelativeLinearAccel(),
   165   this->
link->RelativeAngularAccel());
   169     this->
link->GetRelativeLinearVel().Ign(),
   170     this->
link->GetRelativeAngularVel().Ign());
   174     this->
link->GetWorldLinearVel().Ign(),
   175     this->
link->GetWorldAngularVel().Ign());
   180     this->
link->GetWorldLinearAccel().Ign(),
   181     this->
link->GetWorldAngularAccel().Ign());
   185     this->
link->GetRelativeLinearAccel().Ign(),
   186     this->
link->GetRelativeAngularAccel().Ign());
   190   ignition::math::Matrix3d R_b_w = ignition::math::Matrix3d(pose_w_b.Rot().Inverse());
   194   R6_b_w_eigen << R_b_w_eigen, Eigen::Matrix3d::Zero(),
   195                   Eigen::Matrix3d::Zero(), R_b_w_eigen;
 
void publish(const boost::shared_ptr< M > &message) const 
gazebo::event::ConnectionPtr updateConnection
Update event. 
gazebo::physics::WorldPtr world
Pointer to the world plugin. 
ROSCPP_DECL bool isInitialized()
GZ_REGISTER_MODEL_PLUGIN(UmbilicalPlugin)
common::Time lastTime
Time stamp of previous time step. 
ros::Publisher pub_accel_b_numeric
ros::Publisher pub_accel_w_gazebo
Eigen::Matrix3d Matrix3ToEigen(const ignition::math::Matrix3d &m)
gazebo::physics::ModelPtr model
Pointer to the model structure. 
Eigen::Matrix< double, 6, 1 > Vector6d
virtual void Connect()
Connects the update event callback. 
ros::Publisher pub_accel_w_numeric
virtual ~AccelerationsTestPlugin()
Destructor. 
geometry_msgs::Accel accelFromEigen(const Eigen::Vector6d &acc)
void Update(const gazebo::common::UpdateInfo &_info)
Update the simulation state. 
boost::scoped_ptr< ros::NodeHandle > rosNode
ros::Publisher pub_accel_b_gazebo
Eigen::Vector6d EigenStack(const ignition::math::Vector3d &_x, const ignition::math::Vector3d &_y)
Eigen::Matrix< double, 6, 6 > Matrix6d
physics::LinkPtr link
Link of test object. 
Eigen::Vector6d last_w_v_w_b
Velocity of link with respect to world frame in previous time step. 
virtual void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf)
gazebo::transport::NodePtr node
Gazebo node.