#include <gazebo_ros_sim_iface.h>
Public Member Functions | |
GazeboRosSimIface (Entity *parent) | |
Constructor. | |
virtual | ~GazeboRosSimIface () |
Destructor. | |
Protected Member Functions | |
virtual void | FiniChild () |
Finalize the controller, unadvertise topics. | |
virtual void | InitChild () |
Init the controller. | |
virtual void | LoadChild (XMLConfigNode *node) |
Load the controller. | |
virtual void | UpdateChild () |
Update the controller. | |
Private Member Functions | |
void | QueueThread () |
bool | ServiceCallback (gazebo_plugins::SetPose::Request &req, gazebo_plugins::SetPose::Response &res) |
call back when using service | |
void | UpdateObjectPose (const nav_msgs::Odometry::ConstPtr &poseMsg) |
call back when a Odometry message is published | |
Private Attributes | |
Vector3 | angVel |
ParamT< Vector3 > * | angVelP |
boost::thread | callback_queue_thread_ |
std::string | frameName |
boost::mutex | lock |
A mutex to lock access to fields that are used in ROS message callbacks. | |
std::string | modelName |
ParamT< std::string > * | modelNameP |
Body * | myFrame |
Entity * | myParent |
A pointer to the parent entity. | |
ros::CallbackQueue | queue_ |
std::string | robotNamespace |
ParamT< std::string > * | robotNamespaceP |
for setting ROS name space | |
ros::NodeHandle * | rosnode_ |
A pointer to the ROS node. A node will be instantiated if it does not exist. | |
Vector3 | rpy |
ParamT< Vector3 > * | rpyP |
std::string | serviceName |
ParamT< std::string > * | serviceNameP |
ros::ServiceServer | srv_ |
ros::Subscriber | sub_ |
std::string | topicName |
ParamT< std::string > * | topicNameP |
ROS Pose topic name. | |
Vector3 | vel |
ParamT< Vector3 > * | velP |
Vector3 | xyz |
ParamT< Vector3 > * | xyzP |
Definition at line 79 of file gazebo_ros_sim_iface.h.
GazeboRosSimIface::GazeboRosSimIface | ( | Entity * | parent | ) |
Constructor.
parent | The parent entity, must be a Model or a Sensor |
Definition at line 52 of file gazebo_ros_sim_iface.cpp.
GazeboRosSimIface::~GazeboRosSimIface | ( | ) | [virtual] |
Destructor.
Definition at line 75 of file gazebo_ros_sim_iface.cpp.
void GazeboRosSimIface::FiniChild | ( | ) | [protected, virtual] |
Finalize the controller, unadvertise topics.
Definition at line 308 of file gazebo_ros_sim_iface.cpp.
void GazeboRosSimIface::InitChild | ( | ) | [protected, virtual] |
Init the controller.
Definition at line 217 of file gazebo_ros_sim_iface.cpp.
void GazeboRosSimIface::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Load the controller.
node | XML config node |
Definition at line 92 of file gazebo_ros_sim_iface.cpp.
void GazeboRosSimIface::QueueThread | ( | ) | [private] |
Definition at line 320 of file gazebo_ros_sim_iface.cpp.
bool GazeboRosSimIface::ServiceCallback | ( | gazebo_plugins::SetPose::Request & | req, | |
gazebo_plugins::SetPose::Response & | res | |||
) | [private] |
call back when using service
if a relative Body frame is specified, set pose relative to this Body frame if frameName specified is "world", "/map" or "map", set relative to the gazebo inertial world
Definition at line 140 of file gazebo_ros_sim_iface.cpp.
void GazeboRosSimIface::UpdateChild | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 299 of file gazebo_ros_sim_iface.cpp.
void GazeboRosSimIface::UpdateObjectPose | ( | const nav_msgs::Odometry::ConstPtr & | poseMsg | ) | [private] |
call back when a Odometry message is published
Definition at line 225 of file gazebo_ros_sim_iface.cpp.
Vector3 gazebo::GazeboRosSimIface::angVel [private] |
Definition at line 126 of file gazebo_ros_sim_iface.h.
ParamT<Vector3> * gazebo::GazeboRosSimIface::angVelP [private] |
Definition at line 124 of file gazebo_ros_sim_iface.h.
boost::thread gazebo::GazeboRosSimIface::callback_queue_thread_ [private] |
Definition at line 137 of file gazebo_ros_sim_iface.h.
std::string gazebo::GazeboRosSimIface::frameName [private] |
Definition at line 125 of file gazebo_ros_sim_iface.h.
boost::mutex gazebo::GazeboRosSimIface::lock [private] |
A mutex to lock access to fields that are used in ROS message callbacks.
Definition at line 117 of file gazebo_ros_sim_iface.h.
std::string gazebo::GazeboRosSimIface::modelName [private] |
Definition at line 125 of file gazebo_ros_sim_iface.h.
ParamT<std::string> * gazebo::GazeboRosSimIface::modelNameP [private] |
Definition at line 123 of file gazebo_ros_sim_iface.h.
Body* gazebo::GazeboRosSimIface::myFrame [private] |
Definition at line 138 of file gazebo_ros_sim_iface.h.
Entity* gazebo::GazeboRosSimIface::myParent [private] |
A pointer to the parent entity.
Definition at line 109 of file gazebo_ros_sim_iface.h.
ros::CallbackQueue gazebo::GazeboRosSimIface::queue_ [private] |
Definition at line 135 of file gazebo_ros_sim_iface.h.
std::string gazebo::GazeboRosSimIface::robotNamespace [private] |
Definition at line 132 of file gazebo_ros_sim_iface.h.
ParamT<std::string>* gazebo::GazeboRosSimIface::robotNamespaceP [private] |
for setting ROS name space
Definition at line 131 of file gazebo_ros_sim_iface.h.
ros::NodeHandle* gazebo::GazeboRosSimIface::rosnode_ [private] |
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition at line 112 of file gazebo_ros_sim_iface.h.
Vector3 gazebo::GazeboRosSimIface::rpy [private] |
Definition at line 126 of file gazebo_ros_sim_iface.h.
ParamT<Vector3> * gazebo::GazeboRosSimIface::rpyP [private] |
Definition at line 124 of file gazebo_ros_sim_iface.h.
std::string gazebo::GazeboRosSimIface::serviceName [private] |
Definition at line 128 of file gazebo_ros_sim_iface.h.
ParamT<std::string>* gazebo::GazeboRosSimIface::serviceNameP [private] |
Definition at line 127 of file gazebo_ros_sim_iface.h.
ros::ServiceServer gazebo::GazeboRosSimIface::srv_ [private] |
Definition at line 114 of file gazebo_ros_sim_iface.h.
ros::Subscriber gazebo::GazeboRosSimIface::sub_ [private] |
Definition at line 113 of file gazebo_ros_sim_iface.h.
std::string gazebo::GazeboRosSimIface::topicName [private] |
Definition at line 125 of file gazebo_ros_sim_iface.h.
ParamT<std::string>* gazebo::GazeboRosSimIface::topicNameP [private] |
ROS Pose topic name.
ROS frame transform name to use in the pose message header. This should typically match the link name the sensor is attached. inputs
Definition at line 123 of file gazebo_ros_sim_iface.h.
Vector3 gazebo::GazeboRosSimIface::vel [private] |
Definition at line 126 of file gazebo_ros_sim_iface.h.
ParamT<Vector3> * gazebo::GazeboRosSimIface::velP [private] |
Definition at line 124 of file gazebo_ros_sim_iface.h.
Vector3 gazebo::GazeboRosSimIface::xyz [private] |
Definition at line 126 of file gazebo_ros_sim_iface.h.
ParamT<Vector3>* gazebo::GazeboRosSimIface::xyzP [private] |
Definition at line 124 of file gazebo_ros_sim_iface.h.