43 #include <gazebo/physics/physics.hh> 44 #include <gazebo/sensors/sensors.hh> 45 #include <gazebo/common/common.hh> 47 #include <sdf/Param.hh> 59 pr2_gazebo_plugins::SetModelsJointsStates::Response &res)
68 ROS_DEBUG(
"Calling FiniChild in GazeboRosControllerManager");
76 this->controller_manager_queue_.clear();
77 this->controller_manager_queue_.disable();
78 this->controller_manager_callback_queue_thread_.join();
99 std::string modelName = _sdf->GetParent()->Get<std::string>(
"name");
102 this->
world = _parent->GetWorld();
109 gzerr <<
"Unable to get parent model\n";
115 gzdbg <<
"plugin model name: " << modelName <<
"\n";
120 if (getenv(
"CHECK_SPEEDUP"))
122 #if GAZEBO_MAJOR_VERSION >= 8 127 sim_start_ = this->world->GetSimTime().Double();
143 if (_sdf->HasElement(
"robotNamespace"))
147 if (_sdf->HasElement(
"robotParam"))
148 this->
robotParam = _sdf->Get<std::string>(
"robotParam");
167 #if GAZEBO_MAJOR_VERSION >= 8 191 gazebo::physics::JointPtr joint = this->
parent_model_->GetJoint(joint_name);
194 this->
joints_.push_back(joint);
200 this->
joints_.push_back(gazebo::physics::JointPtr());
201 ROS_ERROR(
"A joint named \"%s\" is not part of Mechanism Controlled joints.\n", joint_name.c_str());
209 this->controller_manager_callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosControllerManager::ControllerManagerQueueThread,
this ) );
217 if (this->
world->IsPaused())
return;
219 if (getenv(
"CHECK_SPEEDUP"))
221 #if GAZEBO_MAJOR_VERSION >= 8 228 std::cout <<
" real time: " << wall_elapsed
229 <<
" sim time: " << sim_elapsed
230 <<
" speed up: " << sim_elapsed / wall_elapsed
241 for (
unsigned int i = 0;
i < this->
joints_.size(); ++
i)
248 if (this->
joints_[i]->HasType(gazebo::physics::Base::HINGE_JOINT))
250 gazebo::physics::JointPtr hj = this->
joints_[i];
251 #if GAZEBO_MAJOR_VERSION >= 8 262 else if (this->
joints_[i]->HasType(gazebo::physics::Base::SLIDER_JOINT))
264 gazebo::physics::JointPtr sj = this->
joints_[i];
266 #if GAZEBO_MAJOR_VERSION >= 8 297 #if GAZEBO_MAJOR_VERSION >= 8 307 catch (
const char* c)
309 if (strcmp(c,
"dividebyzero")==0)
310 ROS_WARN(
"pid controller reports divide by zero error");
312 ROS_WARN(
"unknown const char* exception: %s", c);
323 for (
unsigned int i = 0;
i < this->
joints_.size(); ++
i)
330 double damping_coef = 0;
337 if (this->
joints_[i]->HasType(gazebo::physics::Base::HINGE_JOINT))
339 gazebo::physics::JointPtr hj = this->
joints_[i];
340 double current_velocity = hj->GetVelocity(0);
341 double damping_force = damping_coef * current_velocity;
342 double effort_command = effort - damping_force;
343 hj->SetForce(0,effort_command);
347 else if (this->
joints_[i]->HasType(gazebo::physics::Base::SLIDER_JOINT))
349 gazebo::physics::JointPtr sj = this->
joints_[i];
350 double current_velocity = sj->GetVelocity(0);
351 double damping_force = damping_coef * current_velocity;
352 double effort_command = effort-damping_force;
353 sj->SetForce(0,effort_command);
364 std::string urdf_param_name;
365 std::string urdf_string;
367 while(urdf_string.empty())
369 ROS_INFO(
"gazebo controller manager plugin is waiting for urdf: %s on the param server. (make sure there is a rosparam by that name in the ros parameter server, otherwise, this plugin blocks simulation forever).", this->
robotParam.c_str());
373 ROS_DEBUG(
"found upstream\n%s\n------\n%s\n------\n%s",this->
robotParam.c_str(),urdf_param_name.c_str(),urdf_string.c_str());
378 ROS_DEBUG(
"found in node namespace\n%s\n------\n%s\n------\n%s",this->
robotParam.c_str(),urdf_param_name.c_str(),urdf_string.c_str());
382 ROS_INFO(
"gazebo controller manager got pr2.xml from param server, parsing it...");
386 if (!doc.Parse(urdf_string.c_str()) && doc.Error())
388 ROS_ERROR(
"Could not load the gazebo controller manager plugin's configuration file: %s\n",
389 urdf_string.c_str());
397 struct GetActuators :
public TiXmlVisitor
399 std::set<std::string> actuators;
400 virtual bool VisitEnter(
const TiXmlElement &elt,
const TiXmlAttribute *)
402 if (elt.ValueStr() == std::string(
"actuator") && elt.Attribute(
"name"))
403 actuators.insert(elt.Attribute(
"name"));
404 else if (elt.ValueStr() == std::string(
"rightActuator") && elt.Attribute(
"name"))
405 actuators.insert(elt.Attribute(
"name"));
406 else if (elt.ValueStr() == std::string(
"leftActuator") && elt.Attribute(
"name"))
407 actuators.insert(elt.Attribute(
"name"));
411 doc.RootElement()->Accept(&get_actuators);
414 std::set<std::string>::iterator it;
415 for (it = get_actuators.actuators.begin(); it != get_actuators.actuators.end(); ++it)
434 void GazeboRosControllerManager::ControllerManagerQueueThread()
436 ROS_INFO_STREAM(
"Callback thread id=" << boost::this_thread::get_id());
438 static const double timeout = 0.01;
449 ROS_INFO_STREAM(
"Callback thread id=" << boost::this_thread::get_id());
bool addActuator(Actuator *actuator)
pr2_controller_manager::ControllerManager * cm_
ROSCPP_DECL bool isInitialized()
double wall_start_
ros service callback
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual ~GazeboRosControllerManager()
virtual void UpdateChild()
std::string robotParam
set topic name of robot description parameter
std::vector< gazebo::physics::JointPtr > joints_
event::ConnectionPtr updateConnection
void ReadPr2Xml()
Service Call Name.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool getParam(const std::string &key, std::string &s) const
gazebo::physics::ModelPtr parent_model_
void propagateJointPositionToActuatorPosition()
pr2_hardware_interface::HardwareInterface hw_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
virtual ~ControllerManager()
ros::NodeHandle * rosnode_
pr2_mechanism_model::Robot model_
bool initXml(TiXmlElement *config)
bool searchParam(const std::string &key, std::string &result) const
void propagateActuatorEffortToJointEffort()
#define ROS_INFO_STREAM(args)
std::vector< JointState > joint_states_
GazeboRosControllerManager()
boost::thread ros_spinner_thread_
GZ_REGISTER_MODEL_PLUGIN(GazeboRosP3D)
void ControllerManagerROSThread()
pr2_mechanism_model::RobotState * state_
pr2_mechanism_model::RobotState * fake_state_
ROSCPP_DECL void spinOnce()
bool setModelsJointsStates(pr2_gazebo_plugins::SetModelsJointsStates::Request &req, pr2_gazebo_plugins::SetModelsJointsStates::Response &res)
ros service callback
std::string robotNamespace
def shortest_angular_distance(from_angle, to_angle)