#include <gazebo_ros_force.h>
Public Member Functions | |
GazeboRosForce () | |
Constructor. | |
virtual | ~GazeboRosForce () |
Destructor. | |
Protected Member Functions | |
void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
virtual void | UpdateChild () |
Private Member Functions | |
void | QueueThread () |
The custom callback queue thread function. | |
void | UpdateObjectForce (const geometry_msgs::Wrench::ConstPtr &_msg) |
call back when a Wrench message is published | |
Private Attributes | |
boost::thread | callback_queue_thread_ |
Thead object for the running callback Thread. | |
physics::LinkPtr | link_ |
A pointer to the Link, where force is applied. | |
std::string | link_name_ |
The Link this plugin is attached to, and will exert forces on. | |
boost::mutex | lock_ |
A mutex to lock access to fields that are used in ROS message callbacks. | |
ros::CallbackQueue | queue_ |
std::string | robot_namespace_ |
for setting ROS name space | |
ros::NodeHandle * | rosnode_ |
A pointer to the ROS node. A node will be instantiated if it does not exist. | |
ros::Subscriber | sub_ |
std::string | topic_name_ |
ROS Wrench topic name inputs. | |
event::ConnectionPtr | update_connection_ |
physics::WorldPtr | world_ |
A pointer to the gazebo world. | |
geometry_msgs::Wrench | wrench_msg_ |
Container for the wrench force that this plugin exerts on the body. |
Definition at line 71 of file gazebo_ros_force.h.
Constructor.
Definition at line 35 of file gazebo_ros_force.cpp.
gazebo::GazeboRosForce::~GazeboRosForce | ( | ) | [virtual] |
Destructor.
Definition at line 47 of file gazebo_ros_force.cpp.
void gazebo::GazeboRosForce::Load | ( | physics::ModelPtr | _model, |
sdf::ElementPtr | _sdf | ||
) | [protected] |
Definition at line 62 of file gazebo_ros_force.cpp.
void gazebo::GazeboRosForce::QueueThread | ( | ) | [private] |
The custom callback queue thread function.
Definition at line 150 of file gazebo_ros_force.cpp.
void gazebo::GazeboRosForce::UpdateChild | ( | ) | [protected, virtual] |
Definition at line 137 of file gazebo_ros_force.cpp.
void gazebo::GazeboRosForce::UpdateObjectForce | ( | const geometry_msgs::Wrench::ConstPtr & | _msg | ) | [private] |
call back when a Wrench message is published
[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] |
Thead object for the running callback Thread.
Definition at line 116 of file gazebo_ros_force.h.
physics::LinkPtr gazebo::GazeboRosForce::link_ [private] |
A pointer to the Link, where force is applied.
Definition at line 96 of file gazebo_ros_force.h.
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.
Definition at line 114 of file gazebo_ros_force.h.
std::string gazebo::GazeboRosForce::robot_namespace_ [private] |
for setting ROS name space
Definition at line 111 of file gazebo_ros_force.h.
ros::NodeHandle* gazebo::GazeboRosForce::rosnode_ [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.
ros::Subscriber gazebo::GazeboRosForce::sub_ [private] |
Definition at line 100 of file gazebo_ros_force.h.
std::string gazebo::GazeboRosForce::topic_name_ [private] |
ROS Wrench topic name inputs.
Definition at line 106 of file gazebo_ros_force.h.
Definition at line 121 of file gazebo_ros_force.h.
physics::WorldPtr gazebo::GazeboRosForce::world_ [private] |
A pointer to the gazebo world.
Definition at line 93 of file gazebo_ros_force.h.
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.