#include <gazebo_ros_force.h>
|
void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
|
virtual void | UpdateChild () |
|
Definition at line 71 of file gazebo_ros_force.h.
gazebo::GazeboRosForce::GazeboRosForce |
( |
| ) |
|
gazebo::GazeboRosForce::~GazeboRosForce |
( |
| ) |
|
|
virtual |
void gazebo::GazeboRosForce::Load |
( |
physics::ModelPtr |
_model, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
|
protected |
void gazebo::GazeboRosForce::QueueThread |
( |
| ) |
|
|
private |
void gazebo::GazeboRosForce::UpdateChild |
( |
| ) |
|
|
protectedvirtual |
void gazebo::GazeboRosForce::UpdateObjectForce |
( |
const geometry_msgs::Wrench::ConstPtr & |
_msg | ) |
|
|
private |
call back when a Wrench message is published
- Parameters
-
[in] | _msg | The Incoming ROS message representing the new force to exert. |
Definition at line 125 of file gazebo_ros_force.cpp.
boost::thread gazebo::GazeboRosForce::callback_queue_thread_ |
|
private |
physics::LinkPtr gazebo::GazeboRosForce::link_ |
|
private |
std::string gazebo::GazeboRosForce::link_name_ |
|
private |
The Link this plugin is attached to, and will exert forces on.
Definition at line 108 of file gazebo_ros_force.h.
boost::mutex gazebo::GazeboRosForce::lock_ |
|
private |
A mutex to lock access to fields that are used in ROS message callbacks.
Definition at line 103 of file gazebo_ros_force.h.
std::string gazebo::GazeboRosForce::robot_namespace_ |
|
private |
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition at line 99 of file gazebo_ros_force.h.
std::string gazebo::GazeboRosForce::topic_name_ |
|
private |
physics::WorldPtr gazebo::GazeboRosForce::world_ |
|
private |
geometry_msgs::Wrench gazebo::GazeboRosForce::wrench_msg_ |
|
private |
Container for the wrench force that this plugin exerts on the body.
Definition at line 118 of file gazebo_ros_force.h.
The documentation for this class was generated from the following files: