cob_head_axis.cpp
Go to the documentation of this file.
1 /****************************************************************
2  *
3  * Copyright (c) 2010
4  *
5  * Fraunhofer Institute for Manufacturing Engineering
6  * and Automation (IPA)
7  *
8  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
9  *
10  * Project name: care-o-bot
11  * ROS stack name: cob3_driver
12  * ROS package name: cob_head_axis
13  *
14  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
15  *
16  * Author: Ulrich Reiser, email:ulrich.reiser@ipa.fhg.de
17  *
18  * Date of creation: Jan 2010
19  * ToDo:
20  *
21  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
22  *
23  * Redistribution and use in source and binary forms, with or without
24  * modification, are permitted provided that the following conditions are met:
25  *
26  * * Redistributions of source code must retain the above copyright
27  * notice, this list of conditions and the following disclaimer.
28  * * Redistributions in binary form must reproduce the above copyright
29  * notice, this list of conditions and the following disclaimer in the
30  * documentation and/or other materials provided with the distribution.
31  * * Neither the name of the Fraunhofer Institute for Manufacturing
32  * Engineering and Automation (IPA) nor the names of its
33  * contributors may be used to endorse or promote products derived from
34  * this software without specific prior written permission.
35  *
36  * This program is free software: you can redistribute it and/or modify
37  * it under the terms of the GNU Lesser General Public License LGPL as
38  * published by the Free Software Foundation, either version 3 of the
39  * License, or (at your option) any later version.
40  *
41  * This program is distributed in the hope that it will be useful,
42  * but WITHOUT ANY WARRANTY; without even the implied warranty of
43  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
44  * GNU Lesser General Public License LGPL for more details.
45  *
46  * You should have received a copy of the GNU Lesser General Public
47  * License LGPL along with this program.
48  * If not, see <http://www.gnu.org/licenses/>.
49  *
50  ****************************************************************/
51 
52 //##################
53 //#### includes ####
54 
55 // standard includes
56 //--
57 
58 // ROS includes
59 #include <ros/ros.h>
60 #include <urdf/model.h>
62 
63 // ROS message includes
64 #include <sensor_msgs/JointState.h>
65 #include <control_msgs/FollowJointTrajectoryAction.h>
66 #include <control_msgs/JointTrajectoryControllerState.h>
67 #include <diagnostic_msgs/DiagnosticArray.h>
68 
69 // ROS service includes
70 #include <std_srvs/Trigger.h>
71 #include <cob_srvs/SetString.h>
72 #include <cob_srvs/SetFloat.h>
73 
74 // external includes
75 #include <cob_head_axis/ElmoCtrl.h>
76 
77 #include <unistd.h>
78 
79 //####################
80 //#### node class ####
81 class NodeClass
82 {
83  //
84  public:
85  // create a handle for this node, initialize node
88 
89  // declaration of topics to publish
93 
94  // declaration of topics to subscribe, callback is called for new messages arriving
96 
97  // declaration of service servers
103 
104  // declaration of service clients
105  //--
106 
107  // action lib server
109  std::string action_name_;
110  control_msgs::FollowJointTrajectoryFeedback feedback_;
111  control_msgs::FollowJointTrajectoryResult result_;
112 
113  // global variables
116 
117  std::string CanDevice_;
118  std::string CanIniFile_;
122  double MaxVel_;
123  int ModID_;
124  std::string operationMode_;
125  double LowerLimit_;
126  double UpperLimit_;
127  double Offset_;
130  double GearRatio_;
131 
132  std::string JointName_;
134  bool isError_;
135  bool finished_;
136  double ActualPos_;
137  double ActualVel_;
138  double GoalPos_;
139  trajectory_msgs::JointTrajectory traj_;
140  trajectory_msgs::JointTrajectoryPoint traj_point_;
141  unsigned int traj_point_nr_;
142 
143  // Constructor
145  as_(n_, "joint_trajectory_controller/follow_joint_trajectory", boost::bind(&NodeClass::executeCB, this, _1), false),
146  action_name_("follow_joint_trajectory")
147  {
148  n_private_ = ros::NodeHandle("~");
149 
150  isInitialized_ = false;
151  isError_ = false;
152  ActualPos_=0.0;
153  ActualVel_=0.0;
154 
155  CamAxis_ = new ElmoCtrl();
156  CamAxisParams_ = new ElmoCtrlParams();
157 
158  // implementation of topics to publish
159  topicPub_JointState_ = n_.advertise<sensor_msgs::JointState>("joint_states", 1);
160  topicPub_ControllerState_ = n_.advertise<control_msgs::JointTrajectoryControllerState>("joint_trajectory_controller/state", 1);
161  topicPub_Diagnostic_ = n_.advertise<diagnostic_msgs::DiagnosticArray>("diagnostics", 1);
162 
163 
164  // implementation of topics to subscribe
165 
166  // implementation of service servers
167  srvServer_Init_ = n_.advertiseService("driver/init", &NodeClass::srvCallback_Init, this);
168  srvServer_Stop_ = n_.advertiseService("driver/stop", &NodeClass::srvCallback_Stop, this);
169  srvServer_Recover_ = n_.advertiseService("driver/recover", &NodeClass::srvCallback_Recover, this);
170  srvServer_SetOperationMode_ = n_.advertiseService("driver/set_operation_mode", &NodeClass::srvCallback_SetOperationMode, this);
171  srvServer_SetDefaultVel_ = n_.advertiseService("driver/set_default_vel", &NodeClass::srvCallback_SetDefaultVel, this);
172 
173  // implementation of service clients
174  //--
175 
176  // read parameters from parameter server
177  ROS_INFO("Namespace: %s", n_private_.getNamespace().c_str());
178  if(!n_private_.hasParam("EnoderIncrementsPerRevMot")) ROS_WARN("cob_head_axis: couldn't find parameter EnoderIncrementsPerRevMot, check if ALL parameters have been set correctly");
179 
180  n_private_.param<std::string>("CanDevice", CanDevice_, "PCAN");
181  n_private_.param<int>("CanBaudrate", CanBaudrate_, 500);
182  n_private_.param<int>("HomingDir", HomingDir_, 1);
183  n_private_.param<int>("HomingDigIn", HomingDigIn_, 11);
184  n_private_.param<int>("ModId",ModID_, 17);
185  n_private_.param<std::string>("JointName",JointName_, "head_axis_joint");
186  n_private_.param<std::string>("CanIniFile",CanIniFile_, "/");
187  n_private_.param<std::string>("operation_mode",operationMode_, "position");
188  n_private_.param<int>("MotorDirection",MotorDirection_, 1);
189  n_private_.param<double>("GearRatio",GearRatio_, 62.5);
190  n_private_.param<int>("EnoderIncrementsPerRevMot",EnoderIncrementsPerRevMot_, 4096);
191 
192  ROS_INFO("CanDevice=%s, CanBaudrate=%d, ModID=%d, HomingDigIn=%d",CanDevice_.c_str(),CanBaudrate_,ModID_,HomingDigIn_);
193 
194 
195  // load parameter server string for robot/model
196  std::string xml_string;
197  n_.getParam("/robot_description",xml_string);
198  if (xml_string.size()==0)
199  {
200  ROS_ERROR("Unable to load robot model from param server robot_description\n");
201  exit(2);
202  }
203 
204  // extract limits and velocitys from urdf model
205  urdf::Model model;
206  if (!model.initString(xml_string))
207  {
208  ROS_ERROR("Failed to parse urdf file");
209  exit(2);
210  }
211  ROS_INFO("Successfully parsed urdf file");
212 
213  // get LowerLimits out of urdf model
214  LowerLimit_ = model.getJoint(JointName_.c_str())->limits->lower;
215  //std::cout << "LowerLimits[" << JointNames[i].c_str() << "] = " << LowerLimits[i] << std::endl;
216  CamAxisParams_->SetLowerLimit(LowerLimit_);
217 
218  // get UpperLimits out of urdf model
219  UpperLimit_ = model.getJoint(JointName_.c_str())->limits->upper;
220  //std::cout << "LowerLimits[" << JointNames[i].c_str() << "] = " << LowerLimits[i] << std::endl;
221  CamAxisParams_->SetUpperLimit(UpperLimit_);
222 
223  // get Offset out of urdf model
224  //calibration rising no longer supported
225  //Offset_ = model.getJoint(JointName_.c_str())->calibration->rising.get()[0];
226  Offset_ = 0.0;
227  //std::cout << "Offset[" << JointNames[i].c_str() << "] = " << Offsets[i] << std::endl;
228  CamAxisParams_->SetAngleOffset(Offset_);
229 
230  // get velocitiy out of urdf model
231  MaxVel_ = model.getJoint(JointName_.c_str())->limits->velocity;
232  ROS_INFO("Successfully read limits from urdf");
233 
234 
235  //initializing and homing of camera_axis
236  CamAxisParams_->SetCanIniFile(CanIniFile_);
237  CamAxisParams_->SetHomingDir(HomingDir_);
238  CamAxisParams_->SetHomingDigIn(HomingDigIn_);
239  CamAxisParams_->SetMaxVel(MaxVel_);
240  CamAxisParams_->SetGearRatio(GearRatio_);
241  CamAxisParams_->SetMotorDirection(MotorDirection_);
242  CamAxisParams_->SetEncoderIncrements(EnoderIncrementsPerRevMot_);
243 
244  CamAxisParams_->Init(CanDevice_, CanBaudrate_, ModID_);
245 
246 
247  //finally start action_server
248  as_.start();
249  }
250 
251  // Destructor
253  {
254  delete CamAxis_;
255  }
256 
257  void executeCB(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal) {
258  if(isInitialized_) {
259  ROS_INFO("Received new goal trajectory with %lu points",goal->trajectory.points.size());
260  // saving goal into local variables
261  traj_ = goal->trajectory;
262  traj_point_nr_ = 0;
263  traj_point_ = traj_.points[traj_point_nr_];
264  GoalPos_ = traj_point_.positions[0];
265  finished_ = false;
266 
267  // stoping axis to prepare for new trajectory
268  CamAxis_->Stop();
269 
270  // check that preempt has not been requested by the client
271  if (as_.isPreemptRequested())
272  {
273  ROS_INFO("%s: Preempted %s", n_.getNamespace().c_str(), action_name_.c_str());
274  // set the action state to preempted
275  as_.setPreempted();
276  }
277 
278  usleep(2000000); // needed sleep until drive starts to change status from idle to moving
279 
280  while (not finished_)
281  {
282  if (as_.isNewGoalAvailable())
283  {
284  ROS_WARN("%s: Aborted %s", n_.getNamespace().c_str(), action_name_.c_str());
285  as_.setAborted();
286  return;
287  }
288  usleep(10000);
289  //feedback_ =
290  //as_.send feedback_
291  }
292 
293  // set the action state to succeed
294  //result_.result.data = "executing trajectory";
295  ROS_INFO("%s: Succeeded %s", n_.getNamespace().c_str(), action_name_.c_str());
296  // set the action state to succeeded
297  as_.setSucceeded(result_);
298 
299  } else {
300  as_.setAborted();
301  ROS_WARN("Camera_axis not initialized yet!");
302  }
303  }
304 
305  // service callback functions
306  // function will be called when a service is querried
307  bool srvCallback_Init(std_srvs::Trigger::Request &req,
308  std_srvs::Trigger::Response &res )
309  {
310  if (isInitialized_ == false) {
311  ROS_INFO("...initializing camera axis...");
312  // init axis
313  if (CamAxis_->Init(CamAxisParams_))
314  {
315  CamAxis_->setGearPosVelRadS(0.0f, MaxVel_);
316  ROS_INFO("Initializing of camera axis successfully");
317  isInitialized_ = true;
318  res.success = true;
319  res.message = "initializing camera axis successfully";
320  }
321  else
322  {
323  ROS_ERROR("Initializing camera axis not successfully \n");
324  res.success = false;
325  res.message = "initializing camera axis not successfully";
326  }
327  }
328  else
329  {
330  ROS_WARN("...camera axis already initialized...");
331  res.success = true;
332  res.message = "camera axis already initialized";
333  }
334 
335  return true;
336  }
337 
338  bool srvCallback_Stop(std_srvs::Trigger::Request &req,
339  std_srvs::Trigger::Response &res )
340  {
341  ROS_INFO("Stopping camera axis");
342  if(isInitialized_)
343  {
344  // stopping all movements
345  if (CamAxis_->Stop()) {
346  ROS_INFO("Stopping camera axis successfully");
347  res.success = true;
348  res.message = "camera axis stopped successfully";
349  }
350  else {
351  ROS_ERROR("Stopping camera axis not successfully. error");
352  res.success = false;
353  res.message = "stopping camera axis not successfully";
354  }
355  }
356  return true;
357  }
358 
359  bool srvCallback_Recover(std_srvs::Trigger::Request &req,
360  std_srvs::Trigger::Response &res )
361  {
362  if (isInitialized_) {
363  ROS_INFO("Recovering camera axis");
364 
365  // stopping all arm movements
366  if (CamAxis_->RecoverAfterEmergencyStop()) {
367  ROS_INFO("Recovering camera axis successfully");
368  res.success = true;
369  res.message = "camera axis successfully recovered";
370  } else {
371  ROS_ERROR("Recovering camera axis not successfully. error");
372  res.success = false;
373  res.message = "recovering camera axis failed";
374  }
375  } else {
376  ROS_WARN("...camera axis already recovered...");
377  res.success = true;
378  res.message = "camera axis already recovered";
379  }
380 
381  return true;
382  }
383 
391  bool srvCallback_SetOperationMode( cob_srvs::SetString::Request &req,
392  cob_srvs::SetString::Response &res )
393  {
394  ROS_INFO("Set operation mode to [%s]", req.data.c_str());
395  n_.setParam("operation_mode", req.data.c_str());
396  res.success = true; // 0 = true, else = false
397  return true;
398  }
399 
407  bool srvCallback_SetDefaultVel( cob_srvs::SetFloat::Request &req,
408  cob_srvs::SetFloat::Response &res )
409  {
410  ROS_INFO("Set default velocity to [%f]", req.data);
411  MaxVel_ = req.data;
412  CamAxisParams_->SetMaxVel(MaxVel_);
413  CamAxis_->setMaxVelocity(MaxVel_);
414  res.success = true; // 0 = true, else = false
415  return true;
416  }
417 
418  // other function declarations
420  {
421  if (isInitialized_ == true)
422  {
423  if (operationMode_ == "position")
424  {
425  ROS_DEBUG("moving head_axis in position mode");
426 
427  if (fabs(ActualVel_) < 0.02)
428  {
429  //feedback_.isMoving = false;
430 
431  ROS_DEBUG("next point is %d from %lu",traj_point_nr_,traj_.points.size());
432 
433  if (traj_point_nr_ < traj_.points.size())
434  {
435  // if axis is not moving and not reached last point of trajectory, then send new target point
436  ROS_INFO("...moving to trajectory point[%d], %f",traj_point_nr_,traj_.points[traj_point_nr_].positions[0]);
437  traj_point_ = traj_.points[traj_point_nr_];
438  CamAxis_->setGearPosVelRadS(traj_point_.positions[0], MaxVel_);
439  usleep(900000);
440  CamAxis_->m_Joint->requestPosVel();
441  traj_point_nr_++;
442  //feedback_.isMoving = true;
443  //feedback_.pointNr = traj_point_nr;
444  //as_.publishFeedback(feedback_);
445  }
446  else if ( fabs( fabs(ActualPos_) - fabs(GoalPos_) ) < 0.5*M_PI/180.0 && !finished_ )
447  {
448  ROS_DEBUG("...reached end of trajectory");
449  finished_ = true;
450  }
451  else
452  {
453  //do nothing until GoalPos_ is reached
454  }
455  }
456  else
457  {
458  ROS_DEBUG("...axis still moving to point[%d]",traj_point_nr_);
459  }
460  }
461  else if (operationMode_ == "velocity")
462  {
463  ROS_WARN("Moving in velocity mode currently disabled");
464  }
465  else
466  {
467  ROS_ERROR("axis neither in position nor in velocity mode. OperationMode = [%s]", operationMode_.c_str());
468  }
469  }
470  else
471  {
472  ROS_DEBUG("axis not initialized");
473  }
474  }
475 
477  {
478 
479  if (isInitialized_ == true) {
480  isError_ = CamAxis_->isError();
481 
482  // create message
483  int DOF = 1;
484 
485  CamAxis_->evalCanBuffer();
486  CamAxis_->getGearPosVelRadS(&ActualPos_,&ActualVel_);
487  CamAxis_->m_Joint->requestPosVel();
488 
489  // really bad hack
490  ActualPos_ = HomingDir_ * ActualPos_;
491  ActualVel_ = HomingDir_ * ActualVel_;
492 
493  sensor_msgs::JointState msg;
494  msg.header.stamp = ros::Time::now();
495  msg.name.resize(DOF);
496  msg.position.resize(DOF);
497  msg.velocity.resize(DOF);
498  msg.effort.resize(DOF);
499 
500  msg.name[0] = JointName_;
501  msg.position[0] = ActualPos_;
502  msg.velocity[0] = ActualVel_;
503  msg.effort[0] = 0.0;
504 
505 
506  //std::cout << "Joint " << msg.name[0] <<": pos="<< msg.position[0] << " vel=" << msg.velocity[0] << std::endl;
507 
508  // publish message
509  topicPub_JointState_.publish(msg);
510 
511  // publish controller state message
512  control_msgs::JointTrajectoryControllerState controllermsg;
513  controllermsg.header = msg.header;
514  controllermsg.joint_names.resize(DOF);
515  controllermsg.desired.positions.resize(DOF);
516  controllermsg.desired.velocities.resize(DOF);
517  controllermsg.actual.positions.resize(DOF);
518  controllermsg.actual.velocities.resize(DOF);
519  controllermsg.error.positions.resize(DOF);
520  controllermsg.error.velocities.resize(DOF);
521 
522  controllermsg.joint_names = msg.name;
523  controllermsg.desired.positions = msg.position;
524  controllermsg.desired.velocities = msg.velocity;
525  controllermsg.actual.positions = msg.position;
526  controllermsg.actual.velocities = msg.velocity;
527  // error, calculated out of desired and actual values
528  for (int i = 0; i<DOF; i++ )
529  {
530  controllermsg.error.positions[i] = controllermsg.desired.positions[i] - controllermsg.actual.positions[i];
531  controllermsg.error.velocities[i] = controllermsg.desired.velocities[i] - controllermsg.actual.velocities[i];
532  }
533  topicPub_ControllerState_.publish(controllermsg);
534  }
535  // publishing diagnotic messages
536  diagnostic_msgs::DiagnosticArray diagnostics;
537  diagnostics.status.resize(1);
538  // set data to diagnostics
539  if(isError_)
540  {
541  diagnostics.status[0].level = 2;
542  diagnostics.status[0].name = n_.getNamespace();
543  diagnostics.status[0].message = "drive is in error mode";
544  }
545  else
546  {
547  if (isInitialized_)
548  {
549  diagnostics.status[0].level = 0;
550  diagnostics.status[0].name = n_.getNamespace();
551  diagnostics.status[0].message = "head axis initialized and running";
552  }
553  else
554  {
555  diagnostics.status[0].level = 1;
556  diagnostics.status[0].name = n_.getNamespace();
557  diagnostics.status[0].message = "head axis not initialized";
558  }
559  }
560  // publish diagnostic message
561  topicPub_Diagnostic_.publish(diagnostics);
562  }
563 
564 }; //NodeClass
565 
566 
567 //#######################
568 //#### main programm ####
569 int main(int argc, char** argv)
570 {
571  // initialize ROS, spezify name of node
572  ros::init(argc, argv, "cob_camera_axis");
573 
574  // create nodeClass
575  NodeClass nodeClass;
576 
577  // main loop
578  ros::Rate loop_rate(10); // Hz
579  while(nodeClass.n_.ok()) {
580 
581  // publish JointState
582  nodeClass.publishJointState();
583 
584  // update commands
585  nodeClass.updateCommands();
586 
587  // sleep and waiting for messages, callbacks
588  ros::spinOnce();
589  loop_rate.sleep();
590  }
591 
592  return 0;
593 }
594 
ros::Publisher topicPub_Diagnostic_
control_msgs::FollowJointTrajectoryFeedback feedback_
std::string CanDevice_
bool Init(ElmoCtrlParams *params, bool home=true)
Definition: ElmoCtrl.cpp:164
bool srvCallback_Recover(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer srvServer_Stop_
void executeCB(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
void SetLowerLimit(double LowerLimit)
Definition: ElmoCtrl.h:114
ElmoCtrl * CamAxis_
ros::ServiceServer srvServer_Recover_
void publish(const boost::shared_ptr< M > &message) const
bool initString(const std::string &xmlstring)
bool srvCallback_Init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
int getGearPosVelRadS(double *pdAngleGearRad, double *pdVelGearRadS)
Definition: ElmoCtrl.cpp:421
f
void SetHomingDir(int dir)
Definition: ElmoCtrl.h:125
void SetCanIniFile(std::string iniFile)
Definition: ElmoCtrl.h:133
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool isInitialized_
int setGearPosVelRadS(double dPosRad, double dVelRadS)
Definition: ElmoCtrl.cpp:436
void publishJointState()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
int Init(std::string CanDevice, int BaudRate, int ModuleID)
Definition: ElmoCtrl.h:92
double GoalPos_
ros::ServiceServer srvServer_SetOperationMode_
double ActualVel_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
double LowerLimit_
bool Stop()
Definition: ElmoCtrl.cpp:460
std::string action_name_
ros::Publisher topicPub_ControllerState_
ros::NodeHandle n_private_
bool srvCallback_Stop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
double Offset_
void SetUpperLimit(double UpperLimit)
Definition: ElmoCtrl.h:113
ros::Publisher topicPub_JointState_
double ActualPos_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
control_msgs::FollowJointTrajectoryResult result_
trajectory_msgs::JointTrajectory traj_
const std::string & getNamespace() const
double UpperLimit_
int main(int argc, char **argv)
std::string JointName_
double GearRatio_
void SetMotorDirection(int motor_dir)
Definition: ElmoCtrl.h:145
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int EnoderIncrementsPerRevMot_
trajectory_msgs::JointTrajectoryPoint traj_point_
std::string operationMode_
actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > as_
bool sleep()
ros::ServiceServer srvServer_Init_
void SetGearRatio(double gear_ratio)
Definition: ElmoCtrl.h:141
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void updateCommands()
void setMaxVelocity(float radpersec)
Definition: ElmoCtrl.h:191
bool getParam(const std::string &key, std::string &s) const
std::string CanIniFile_
bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
Executes the service callback for set_operation_mode.
static Time now()
CanDriveHarmonica * m_Joint
joint mutexes
Definition: ElmoCtrl.h:236
ros::ServiceServer srvServer_SetDefaultVel_
int evalCanBuffer()
Definition: ElmoCtrl.cpp:128
bool ok() const
bool hasParam(const std::string &key) const
bool RecoverAfterEmergencyStop()
Definition: ElmoCtrl.cpp:148
bool isError()
Definition: ElmoCtrl.cpp:416
void SetEncoderIncrements(int enc_incr)
Definition: ElmoCtrl.h:137
double MaxVel_
ROSCPP_DECL void spinOnce()
void SetMaxVel(double maxVel)
Definition: ElmoCtrl.h:121
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
bool srvCallback_SetDefaultVel(cob_srvs::SetFloat::Request &req, cob_srvs::SetFloat::Response &res)
Executes the service callback for set_default_vel.
void SetHomingDigIn(int dig_in)
Definition: ElmoCtrl.h:129
unsigned int traj_point_nr_
ros::Subscriber topicSub_JointCommand_
ros::NodeHandle n_
ElmoCtrlParams * CamAxisParams_
#define ROS_DEBUG(...)
void SetAngleOffset(double AngleOffset)
Definition: ElmoCtrl.h:115


cob_head_axis
Author(s): Ulrich Reiser
autogenerated on Tue Jul 25 2017 02:22:10