30 #ifndef GAZEBO_CONTROLLER_MANAGER_H 31 #define GAZEBO_CONTROLLER_MANAGER_H 37 #include <boost/thread/mutex.hpp> 42 #include <pr2_gazebo_plugins/SetModelsJointsStates.h> 45 #include <gazebo/physics/World.hh> 46 #include <gazebo/physics/Model.hh> 47 #include <gazebo/physics/physics.hh> 48 #include <gazebo/common/Time.hh> 49 #include <gazebo/common/Plugin.hh> 64 void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
80 std::vector<gazebo::physics::JointPtr>
joints_;
101 pr2_gazebo_plugins::SetModelsJointsStates::Response &res);
119 private:
void ControllerManagerQueueThread();
120 private: boost::thread controller_manager_callback_queue_thread_;
132 private: transport::NodePtr
node;
pr2_controller_manager::ControllerManager * cm_
double wall_start_
ros service callback
virtual ~GazeboRosControllerManager()
virtual void UpdateChild()
std::string robotParam
set topic name of robot description parameter
std::vector< gazebo::physics::JointPtr > joints_
event::ConnectionPtr updateConnection
ros::ServiceServer setModelsJointsStatesService
ros service
void ReadPr2Xml()
Service Call Name.
gazebo::physics::ModelPtr parent_model_
pr2_hardware_interface::HardwareInterface hw_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
ros::NodeHandle * rosnode_
transport::SubscriberPtr statsSub
GazeboRosControllerManager()
boost::thread ros_spinner_thread_
void ControllerManagerROSThread()
pr2_mechanism_model::RobotState * fake_state_
bool setModelsJointsStates(pr2_gazebo_plugins::SetModelsJointsStates::Request &req, pr2_gazebo_plugins::SetModelsJointsStates::Response &res)
ros service callback
std::string robotNamespace