64 #include <sensor_msgs/JointState.h> 65 #include <control_msgs/FollowJointTrajectoryAction.h> 66 #include <control_msgs/JointTrajectoryControllerState.h> 67 #include <diagnostic_msgs/DiagnosticArray.h> 70 #include <std_srvs/Trigger.h> 71 #include <cob_srvs/SetString.h> 72 #include <cob_srvs/SetFloat.h> 111 control_msgs::FollowJointTrajectoryResult
result_;
139 trajectory_msgs::JointTrajectory
traj_;
145 as_(n_,
"joint_trajectory_controller/follow_joint_trajectory",
boost::bind(&
NodeClass::
executeCB, this, _1), false),
146 action_name_(
"follow_joint_trajectory")
150 isInitialized_ =
false;
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);
178 if(!n_private_.
hasParam(
"EnoderIncrementsPerRevMot"))
ROS_WARN(
"cob_head_axis: couldn't find parameter EnoderIncrementsPerRevMot, check if ALL parameters have been set correctly");
185 n_private_.
param<std::string>(
"JointName",
JointName_,
"head_axis_joint");
196 std::string xml_string;
197 n_.
getParam(
"/robot_description",xml_string);
198 if (xml_string.size()==0)
200 ROS_ERROR(
"Unable to load robot model from param server robot_description\n");
211 ROS_INFO(
"Successfully parsed urdf file");
214 LowerLimit_ = model.getJoint(JointName_.c_str())->limits->lower;
219 UpperLimit_ = model.getJoint(JointName_.c_str())->limits->upper;
231 MaxVel_ = model.getJoint(JointName_.c_str())->limits->velocity;
232 ROS_INFO(
"Successfully read limits from urdf");
244 CamAxisParams_->
Init(CanDevice_, CanBaudrate_, ModID_);
257 void executeCB(
const control_msgs::FollowJointTrajectoryGoalConstPtr &goal) {
259 ROS_INFO(
"Received new goal trajectory with %lu points",goal->trajectory.points.size());
261 traj_ = goal->trajectory;
264 GoalPos_ = traj_point_.positions[0];
280 while (not finished_)
301 ROS_WARN(
"Camera_axis not initialized yet!");
308 std_srvs::Trigger::Response &res )
310 if (isInitialized_ ==
false) {
311 ROS_INFO(
"...initializing camera axis...");
313 if (CamAxis_->
Init(CamAxisParams_))
316 ROS_INFO(
"Initializing of camera axis successfully");
317 isInitialized_ =
true;
319 res.message =
"initializing camera axis successfully";
323 ROS_ERROR(
"Initializing camera axis not successfully \n");
325 res.message =
"initializing camera axis not successfully";
330 ROS_WARN(
"...camera axis already initialized...");
332 res.message =
"camera axis already initialized";
339 std_srvs::Trigger::Response &res )
345 if (CamAxis_->
Stop()) {
346 ROS_INFO(
"Stopping camera axis successfully");
348 res.message =
"camera axis stopped successfully";
351 ROS_ERROR(
"Stopping camera axis not successfully. error");
353 res.message =
"stopping camera axis not successfully";
360 std_srvs::Trigger::Response &res )
362 if (isInitialized_) {
367 ROS_INFO(
"Recovering camera axis successfully");
369 res.message =
"camera axis successfully recovered";
371 ROS_ERROR(
"Recovering camera axis not successfully. error");
373 res.message =
"recovering camera axis failed";
376 ROS_WARN(
"...camera axis already recovered...");
378 res.message =
"camera axis already recovered";
392 cob_srvs::SetString::Response &res )
394 ROS_INFO(
"Set operation mode to [%s]", req.data.c_str());
395 n_.
setParam(
"operation_mode", req.data.c_str());
408 cob_srvs::SetFloat::Response &res )
410 ROS_INFO(
"Set default velocity to [%f]", req.data);
421 if (isInitialized_ ==
true)
423 if (operationMode_ ==
"position")
425 ROS_DEBUG(
"moving head_axis in position mode");
427 if (fabs(ActualVel_) < 0.02)
431 ROS_DEBUG(
"next point is %d from %lu",traj_point_nr_,traj_.points.size());
433 if (traj_point_nr_ < traj_.points.size())
436 ROS_INFO(
"...moving to trajectory point[%d], %f",traj_point_nr_,traj_.points[traj_point_nr_].positions[0]);
446 else if ( fabs( fabs(ActualPos_) - fabs(GoalPos_) ) < 0.5*M_PI/180.0 && !finished_ )
448 ROS_DEBUG(
"...reached end of trajectory");
458 ROS_DEBUG(
"...axis still moving to point[%d]",traj_point_nr_);
461 else if (operationMode_ ==
"velocity")
463 ROS_WARN(
"Moving in velocity mode currently disabled");
467 ROS_ERROR(
"axis neither in position nor in velocity mode. OperationMode = [%s]", operationMode_.c_str());
479 if (isInitialized_ ==
true) {
480 isError_ = CamAxis_->
isError();
493 sensor_msgs::JointState msg;
495 msg.name.resize(DOF);
496 msg.position.resize(DOF);
497 msg.velocity.resize(DOF);
498 msg.effort.resize(DOF);
509 topicPub_JointState_.
publish(msg);
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);
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;
528 for (
int i = 0; i<DOF; i++ )
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];
533 topicPub_ControllerState_.
publish(controllermsg);
536 diagnostic_msgs::DiagnosticArray diagnostics;
537 diagnostics.status.resize(1);
541 diagnostics.status[0].level = 2;
543 diagnostics.status[0].message =
"drive is in error mode";
549 diagnostics.status[0].level = 0;
551 diagnostics.status[0].message =
"head axis initialized and running";
555 diagnostics.status[0].level = 1;
557 diagnostics.status[0].message =
"head axis not initialized";
561 topicPub_Diagnostic_.
publish(diagnostics);
569 int main(
int argc,
char** argv)
572 ros::init(argc, argv,
"cob_camera_axis");
579 while(nodeClass.
n_.
ok()) {
ros::Publisher topicPub_Diagnostic_
control_msgs::FollowJointTrajectoryFeedback feedback_
bool Init(ElmoCtrlParams *params, bool home=true)
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)
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)
void SetHomingDir(int dir)
void SetCanIniFile(std::string iniFile)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int setGearPosVelRadS(double dPosRad, double dVelRadS)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int Init(std::string CanDevice, int BaudRate, int ModuleID)
ros::ServiceServer srvServer_SetOperationMode_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
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(""))
void SetUpperLimit(double UpperLimit)
ros::Publisher topicPub_JointState_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
control_msgs::FollowJointTrajectoryResult result_
trajectory_msgs::JointTrajectory traj_
const std::string & getNamespace() const
int main(int argc, char **argv)
void SetMotorDirection(int motor_dir)
bool isPreemptRequested()
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_
ros::ServiceServer srvServer_Init_
void SetGearRatio(double gear_ratio)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void setMaxVelocity(float radpersec)
bool getParam(const std::string &key, std::string &s) const
bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
Executes the service callback for set_operation_mode.
CanDriveHarmonica * m_Joint
joint mutexes
ros::ServiceServer srvServer_SetDefaultVel_
bool hasParam(const std::string &key) const
bool RecoverAfterEmergencyStop()
void SetEncoderIncrements(int enc_incr)
ROSCPP_DECL void spinOnce()
void SetMaxVel(double maxVel)
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)
bool isNewGoalAvailable()
unsigned int traj_point_nr_
ros::Subscriber topicSub_JointCommand_
ElmoCtrlParams * CamAxisParams_
void SetAngleOffset(double AngleOffset)