test_controller.cpp
Go to the documentation of this file.
1 #include "test_controller.h"
3 #include <boost/thread/condition.hpp>
4 
5 using namespace my_controller_ns;
6 
7 
10  ros::NodeHandle &n)
11 {
12  // copy robot pointer so we can access time
13  robot_ = robot;
14 
15 
16  // get joint
17  // ----------
18  std::string joint_name;
19  if (!n.getParam("joint_name", joint_name))
20  {
21  ROS_ERROR("No joint name given in namespace: '%s')", n.getNamespace().c_str());
22  return false;
23  }
24  joint_state_ = robot->getJointState(joint_name);
25  if (!joint_state_)
26  {
27  ROS_ERROR("MyController could not find joint named '%s'",
28  joint_name.c_str());
29  return false;
30  }
31  if (!joint_state_->joint_->limits)
32  {
33  ROS_ERROR("MyController could not find limits of joint '%s'",
34  joint_name.c_str());
35  return false;
36  }
37  max_effort_ = joint_state_->joint_->limits->effort;
38 
39 
40 
41  // get chain
42  // ----------
43  std::string root_name, tip_name;
44  if (!n.getParam("root_name", root_name))
45  {
46  ROS_ERROR("No root name given in namespace: '%s')", n.getNamespace().c_str());
47  return false;
48  }
49  if (!n.getParam("tip_name", tip_name))
50  {
51  ROS_ERROR("No tip name given in namespace: '%s')", n.getNamespace().c_str());
52  return false;
53  }
54  if (!chain_.init(robot, root_name, tip_name))
55  return false;
57 
58  // advertise topic
59  // ----------
60  std::string topic_name;
61  if (!n.getParam("topic_name", topic_name))
62  {
63  ROS_ERROR("No topic name given in namespace: '%s')", n.getNamespace().c_str());
64  return false;
65  }
67  pub_->msg_.name.resize(1);
68  pub_->msg_.name[0] = "";
69  pub_->msg_.effort.resize(1);
70  pub_->msg_.effort[0] = 0.0;
71 
72 
73  // advertise service
74  // ----------
75  std::string service_name;
76  if (!n.getParam("service_name", service_name))
77  {
78  ROS_ERROR("No service name given in namespace: '%s')", n.getNamespace().c_str());
79  return false;
80  }
82  return true;
83 }
84 
87 {
88  counter_ = 0;
90 }
91 
92 
95 {
96  counter_++;
97  if (counter_ > 10 && pub_->trylock()){
98  counter_ = 0;
99  pub_->msg_.effort[0] = fabs(joint_state_->commanded_effort_) - max_effort_; // this should never be greater than zero
100  pub_->unlockAndPublish();
101  }
102 
104 
105  double tmp;
106  tmp = joint_state_->position_;
107  tmp = joint_state_->velocity_;
110  joint_state_->commanded_effort_ = -10000.0; // above max effort
111  else
112  joint_state_->commanded_effort_ = 10000.0; // above max effort
113 }
114 
115 
118 {}
119 
120 
122 bool MyControllerClass::serviceCallback(pr2_mechanism_msgs::LoadController::Request& req,
123  pr2_mechanism_msgs::LoadController::Response& resp)
124 {
125  pub_->msg_.name[0] = req.name;
126  return true;
127 }
128 
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
Register controller to pluginlib.
pr2_mechanism_model::Chain chain_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
boost::shared_ptr< const urdf::Joint > joint_
void starting()
Controller startup in realtime.
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
boost::scoped_ptr< realtime_tools::RealtimePublisher< sensor_msgs::JointState > > pub_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Controller initialization in non-realtime.
void stopping()
Controller stopping in realtime.
void update()
Controller update loop in realtime.
bool getParam(const std::string &key, std::string &s) const
pr2_mechanism_model::JointState * joint_state_
bool init(RobotState *robot_state, const std::string &root, const std::string &tip)
pr2_mechanism_model::RobotState * robot_
bool serviceCallback(pr2_mechanism_msgs::LoadController::Request &req, pr2_mechanism_msgs::LoadController::Response &resp)
Service call.
#define ROS_ERROR(...)
void toKDL(KDL::Chain &chain)


pr2_controller_manager
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Fri Jun 7 2019 22:04:28