00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059 #include <ros/ros.h>
00060 #include <urdf/model.h>
00061 #include <actionlib/server/simple_action_server.h>
00062
00063
00064 #include <sensor_msgs/JointState.h>
00065 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00066
00067
00068 #include <cob_srvs/Trigger.h>
00069 #include <cob_srvs/SetOperationMode.h>
00070 #include <cob_srvs/SetDefaultVel.h>
00071
00072
00073 #include <cob_camera_axis/ElmoCtrl.h>
00074
00075
00076
00077 class NodeClass
00078 {
00079
00080 public:
00081
00082 ros::NodeHandle n_;
00083
00084
00085 ros::Publisher topicPub_JointState_;
00086
00087
00088 ros::Subscriber topicSub_JointCommand_;
00089
00090
00091 ros::ServiceServer srvServer_Init_;
00092 ros::ServiceServer srvServer_Stop_;
00093 ros::ServiceServer srvServer_Recover_;
00094 ros::ServiceServer srvServer_SetOperationMode_;
00095 ros::ServiceServer srvServer_SetDefaultVel_;
00096
00097
00098
00099
00100
00101 actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction> as_;
00102 std::string action_name_;
00103 pr2_controllers_msgs::JointTrajectoryFeedback feedback_;
00104 pr2_controllers_msgs::JointTrajectoryResult result_;
00105
00106
00107 ElmoCtrl * CamAxis_;
00108 ElmoCtrlParams* CamAxisParams_;
00109
00110 std::string CanDevice_;
00111 std::string CanIniFile_;
00112 int CanBaudrate_;
00113 int HomingDir_;
00114 int HomingDigIn_;
00115 double MaxVel_;
00116 int ModID_;
00117 std::string operationMode_;
00118 double LowerLimit_;
00119 double UpperLimit_;
00120 double Offset_;
00121 int MotorDirection_;
00122 int EnoderIncrementsPerRevMot_;
00123 double GearRatio_;
00124
00125 std::string JointName_;
00126 bool isInitialized_;
00127 bool finished_;
00128 double ActualPos_;
00129 double ActualVel_;
00130 trajectory_msgs::JointTrajectory traj_;
00131 trajectory_msgs::JointTrajectoryPoint traj_point_;
00132 int traj_point_nr_;
00133
00134
00135 NodeClass(std::string name):
00136 as_(n_, name, boost::bind(&NodeClass::executeCB, this, _1)),
00137 action_name_(name)
00138 {
00139 isInitialized_ = false;
00140 ActualPos_=0.0;
00141 ActualVel_=0.0;
00142
00143 CamAxis_ = new ElmoCtrl();
00144 CamAxisParams_ = new ElmoCtrlParams();
00145
00146
00147 topicPub_JointState_ = n_.advertise<sensor_msgs::JointState>("/joint_states", 1);
00148
00149
00150
00151
00152 srvServer_Init_ = n_.advertiseService("init", &NodeClass::srvCallback_Init, this);
00153 srvServer_Stop_ = n_.advertiseService("stop", &NodeClass::srvCallback_Stop, this);
00154 srvServer_Recover_ = n_.advertiseService("recover", &NodeClass::srvCallback_Recover, this);
00155 srvServer_SetOperationMode_ = n_.advertiseService("set_operation_mode", &NodeClass::srvCallback_SetOperationMode, this);
00156 srvServer_SetDefaultVel_ = n_.advertiseService("set_default_vel", &NodeClass::srvCallback_SetDefaultVel, this);
00157
00158
00159
00160
00161
00162 if(!n_.hasParam("EnoderIncrementsPerRevMot")) ROS_WARN("cob_head_axis: couldn't find parameter EnoderIncrementsPerRevMot, check if ALL parameters have been set correctly");
00163
00164 n_.param<std::string>("CanDevice", CanDevice_, "PCAN");
00165 n_.param<int>("CanBaudrate", CanBaudrate_, 500);
00166 n_.param<int>("HomingDir", HomingDir_, 1);
00167 n_.param<int>("HomingDigIn", HomingDigIn_, 11);
00168 n_.param<int>("ModId",ModID_, 17);
00169 n_.param<std::string>("JointName",JointName_, "head_axis_joint");
00170 n_.param<std::string>("CanIniFile",CanIniFile_, "/");
00171 n_.param<std::string>("operation_mode",operationMode_, "position");
00172 n_.param<int>("MotorDirection",MotorDirection_, 1);
00173 n_.param<double>("GearRatio",GearRatio_, 62.5);
00174 n_.param<int>("EnoderIncrementsPerRevMot",EnoderIncrementsPerRevMot_, 4096);
00175
00176 ROS_INFO("CanDevice=%s, CanBaudrate=%d, ModID=%d, HomingDigIn=%d",CanDevice_.c_str(),CanBaudrate_,ModID_,HomingDigIn_);
00177
00178
00179
00180 std::string param_name = "/robot_description";
00181 std::string full_param_name;
00182 std::string xml_string;
00183 n_.searchParam(param_name,full_param_name);
00184 n_.getParam(full_param_name.c_str(),xml_string);
00185 ROS_INFO("full_param_name=%s",full_param_name.c_str());
00186 if (xml_string.size()==0)
00187 {
00188 ROS_ERROR("Unable to load robot model from param server robot_description\n");
00189 exit(2);
00190 }
00191 ROS_DEBUG("%s content\n%s", full_param_name.c_str(), xml_string.c_str());
00192
00193
00194
00195 urdf::Model model;
00196 if (!model.initString(xml_string))
00197 {
00198 ROS_ERROR("Failed to parse urdf file");
00199 exit(2);
00200 }
00201 ROS_INFO("Successfully parsed urdf file");
00202
00203
00204 LowerLimit_ = model.getJoint(JointName_.c_str())->limits->lower;
00205
00206 CamAxisParams_->SetLowerLimit(LowerLimit_);
00207
00208
00209 UpperLimit_ = model.getJoint(JointName_.c_str())->limits->upper;
00210
00211 CamAxisParams_->SetUpperLimit(UpperLimit_);
00212
00213
00214 Offset_ = model.getJoint(JointName_.c_str())->calibration->rising.get()[0];
00215
00216 CamAxisParams_->SetAngleOffset(Offset_);
00217
00218
00219 MaxVel_ = model.getJoint(JointName_.c_str())->limits->velocity;
00220 ROS_INFO("Successfully read limits from urdf");
00221
00222
00223
00224 CamAxisParams_->SetCanIniFile(CanIniFile_);
00225 CamAxisParams_->SetHomingDir(HomingDir_);
00226 CamAxisParams_->SetHomingDigIn(HomingDigIn_);
00227 CamAxisParams_->SetMaxVel(MaxVel_);
00228 CamAxisParams_->SetGearRatio(GearRatio_);
00229 CamAxisParams_->SetMotorDirection(MotorDirection_);
00230 CamAxisParams_->SetEncoderIncrements(EnoderIncrementsPerRevMot_);
00231
00232
00233
00234
00235 CamAxisParams_->Init(CanDevice_, CanBaudrate_, ModID_);
00236
00237
00238 }
00239
00240
00241 ~NodeClass()
00242 {
00243 delete CamAxis_;
00244 }
00245
00246 void executeCB(const pr2_controllers_msgs::JointTrajectoryGoalConstPtr &goal) {
00247 if(isInitialized_) {
00248 ROS_INFO("Received new goal trajectory with %d points",goal->trajectory.points.size());
00249
00250 traj_ = goal->trajectory;
00251 traj_point_nr_ = 0;
00252 traj_point_ = traj_.points[traj_point_nr_];
00253 finished_ = false;
00254
00255
00256 CamAxis_->Stop();
00257
00258
00259 if (as_.isPreemptRequested())
00260 {
00261 ROS_INFO("%s: Preempted", action_name_.c_str());
00262
00263 as_.setPreempted();
00264 }
00265
00266 usleep(2000000);
00267
00268 while(finished_ == false)
00269 {
00270 if (as_.isNewGoalAvailable())
00271 {
00272 ROS_WARN("%s: Aborted", action_name_.c_str());
00273 as_.setAborted();
00274 return;
00275 }
00276 usleep(10000);
00277
00278
00279 }
00280
00281
00282
00283 ROS_INFO("%s: Succeeded", action_name_.c_str());
00284
00285 as_.setSucceeded(result_);
00286
00287 } else {
00288 as_.setAborted();
00289 ROS_WARN("Camera_axis not initialized yet!");
00290 }
00291 }
00292
00293
00294
00295 bool srvCallback_Init(cob_srvs::Trigger::Request &req,
00296 cob_srvs::Trigger::Response &res )
00297 {
00298 if (isInitialized_ == false) {
00299 ROS_INFO("...initializing camera axis...");
00300
00301 if (CamAxis_->Init(CamAxisParams_))
00302 {
00303 ROS_INFO("Initializing of camera axis succesful");
00304 isInitialized_ = true;
00305 res.success.data = true;
00306 res.error_message.data = "initializing camera axis successfull";
00307 }
00308 else
00309 {
00310 ROS_ERROR("Initializing camera axis not succesful \n");
00311 res.success.data = false;
00312 res.error_message.data = "initializing camera axis not successfull";
00313 }
00314 }
00315 else
00316 {
00317 ROS_WARN("...camera axis already initialized...");
00318 res.success.data = true;
00319 res.error_message.data = "camera axis already initialized";
00320 }
00321
00322 return true;
00323 }
00324
00325 bool srvCallback_Stop(cob_srvs::Trigger::Request &req,
00326 cob_srvs::Trigger::Response &res )
00327 {
00328 ROS_INFO("Stopping camera axis");
00329
00330
00331 if (CamAxis_->Stop()) {
00332 ROS_INFO("Stopping camera axis successful");
00333 res.success.data = true;
00334 res.error_message.data = "camera axis stopped successfully";
00335 }
00336 else {
00337 ROS_ERROR("Stopping camera axis not succesful. error");
00338 res.success.data = false;
00339 res.error_message.data = "stopping camera axis not successful";
00340 }
00341
00342 return true;
00343 }
00344
00345 bool srvCallback_Recover(cob_srvs::Trigger::Request &req,
00346 cob_srvs::Trigger::Response &res )
00347 {
00348 if (isInitialized_ == true) {
00349 ROS_INFO("Recovering camera axis");
00350
00351
00352 if (CamAxis_->RecoverAfterEmergencyStop()) {
00353 ROS_INFO("Recovering camera axis succesful");
00354 res.success.data = true;
00355 res.error_message.data = "camera axis successfully recovered";
00356 } else {
00357 ROS_ERROR("Recovering camera axis not succesful. error");
00358 res.success.data = false;
00359 res.error_message.data = "recovering camera axis failed";
00360 }
00361 } else {
00362 ROS_WARN("...camera axis already recovered...");
00363 res.success.data = true;
00364 res.error_message.data = "camera axis already recovered";
00365 }
00366
00367 return true;
00368 }
00369
00377 bool srvCallback_SetOperationMode( cob_srvs::SetOperationMode::Request &req,
00378 cob_srvs::SetOperationMode::Response &res )
00379 {
00380 ROS_INFO("Set operation mode to [%s]", req.operation_mode.data.c_str());
00381 n_.setParam("operation_mode", req.operation_mode.data.c_str());
00382 res.success.data = true;
00383 return true;
00384 }
00385
00393 bool srvCallback_SetDefaultVel( cob_srvs::SetDefaultVel::Request &req,
00394 cob_srvs::SetDefaultVel::Response &res )
00395 {
00396 ROS_INFO("Set default velocity to [%f]", req.default_vel);
00397 MaxVel_ = req.default_vel;
00398 CamAxisParams_->SetMaxVel(MaxVel_);
00399 CamAxis_->setMaxVelocity(MaxVel_);
00400 res.success.data = true;
00401 return true;
00402 }
00403
00404
00405 void updateCommands()
00406 {
00407 if (isInitialized_ == true)
00408 {
00409 if (operationMode_ == "position")
00410 {
00411 ROS_DEBUG("moving head_axis in position mode");
00412 if (ActualVel_ < 0.002)
00413 {
00414
00415
00416 ROS_DEBUG("next point is %d from %d",traj_point_nr_,traj_.points.size());
00417
00418 if (traj_point_nr_ < traj_.points.size())
00419 {
00420
00421 ROS_INFO("...moving to trajectory point[%d], %f",traj_point_nr_,traj_.points[traj_point_nr_].positions[0]);
00422 traj_point_ = traj_.points[traj_point_nr_];
00423 CamAxis_->setGearPosVelRadS(traj_point_.positions[0], MaxVel_);
00424 usleep(900000);
00425 CamAxis_->m_Joint->requestPosVel();
00426 traj_point_nr_++;
00427
00428
00429
00430 }
00431 else
00432 {
00433 ROS_DEBUG("...reached end of trajectory");
00434 finished_ = true;
00435 }
00436 }
00437 else
00438 {
00439 ROS_INFO("...axis still moving to point[%d]",traj_point_nr_);
00440 }
00441 }
00442 else if (operationMode_ == "velocity")
00443 {
00444 ROS_WARN("Moving in velocity mode currently disabled");
00445 }
00446 else
00447 {
00448 ROS_ERROR("axis neither in position nor in velocity mode. OperationMode = [%s]", operationMode_.c_str());
00449 }
00450 }
00451 else
00452 {
00453 ROS_DEBUG("axis not initialized");
00454 }
00455 }
00456
00457 void publishJointState()
00458 {
00459 if (isInitialized_ == true) {
00460
00461 int DOF = 1;
00462
00463 CamAxis_->evalCanBuffer();
00464 CamAxis_->getGearPosVelRadS(&ActualPos_,&ActualVel_);
00465 CamAxis_->m_Joint->requestPosVel();
00466
00467 sensor_msgs::JointState msg;
00468 msg.header.stamp = ros::Time::now();
00469 msg.name.resize(DOF);
00470 msg.position.resize(DOF);
00471 msg.velocity.resize(DOF);
00472
00473 msg.name[0] = JointName_;
00474 msg.position[0] = ActualPos_;
00475 msg.velocity[0] = ActualVel_;
00476
00477
00478
00479
00480
00481 topicPub_JointState_.publish(msg);
00482 }
00483 }
00484
00485 };
00486
00487
00488
00489
00490 int main(int argc, char** argv)
00491 {
00492
00493 ros::init(argc, argv, "cob_camera_axis");
00494
00495
00496 NodeClass nodeClass("joint_trajectory_action");
00497
00498
00499 ros::Rate loop_rate(5);
00500 while(nodeClass.n_.ok()) {
00501
00502
00503 nodeClass.publishJointState();
00504
00505
00506 nodeClass.updateCommands();
00507
00508
00509 ros::spinOnce();
00510 loop_rate.sleep();
00511 }
00512
00513 return 0;
00514 }
00515