/*! * \brief Constructor for PowercubeChainNode class. * * \param name Name for the actionlib server. */ PowercubeChainNode(std::string name): as_(n_, name, boost::bind(&PowercubeChainNode::executeCB, this, _1)), action_name_(name) { sem_can_available = false; can_sem = SEM_FAILED; isInitialized_ = false; traj_point_nr_ = 0; finished_ = false; #ifndef SIMU PCube_ = new PowerCubeCtrl(); #else PCube_ = new simulatedArm(); #endif PCubeParams_ = new PowerCubeCtrlParams(); // implementation of topics to publish topicPub_JointState_ = n_.advertise<sensor_msgs::JointState>("/joint_states", 1); topicPub_ControllerState_ = n_.advertise<pr2_controllers_msgs::JointTrajectoryControllerState>("state", 1); // implementation of topics to subscribe topicSub_DirectCommand_ = n_.subscribe("command", 1, &PowercubeChainNode::topicCallback_DirectCommand, this); // implementation of service servers srvServer_Init_ = n_.advertiseService("init", &PowercubeChainNode::srvCallback_Init, this); srvServer_Stop_ = n_.advertiseService("stop", &PowercubeChainNode::srvCallback_Stop, this); srvServer_Recover_ = n_.advertiseService("recover", &PowercubeChainNode::srvCallback_Recover, this); srvServer_SetOperationMode_ = n_.advertiseService("set_operation_mode", &PowercubeChainNode::srvCallback_SetOperationMode, this); // implementation of service clients //-- // diagnostics updater_.setHardwareID(ros::this_node::getName()); updater_.add("initialization", this, &PowercubeChainNode::diag_init); // read parameters from parameter server n_.getParam("CanModule", CanModule_); n_.getParam("CanDevice", CanDevice_); n_.getParam("CanBaudrate", CanBaudrate_); ROS_INFO("CanModule=%s, CanDevice=%d, CanBaudrate=%d",CanModule_.c_str(),CanDevice_,CanBaudrate_); // get ModIds from parameter server if (n_.hasParam("ModIds")) { n_.getParam("ModIds", ModIds_param_); } else { ROS_ERROR("Parameter ModIds not set"); } ModIds_.resize(ModIds_param_.size()); for (int i = 0; i<ModIds_param_.size(); i++ ) { ModIds_[i] = (int)ModIds_param_[i]; } std::cout << "ModIds = " << ModIds_param_ << std::endl; // get JointNames from parameter server ROS_INFO("getting JointNames from parameter server"); if (n_.hasParam("JointNames")) { n_.getParam("JointNames", JointNames_param_); } else { ROS_ERROR("Parameter JointNames not set"); } JointNames_.resize(JointNames_param_.size()); for (int i = 0; i<JointNames_param_.size(); i++ ) { JointNames_[i] = (std::string)JointNames_param_[i]; } std::cout << "JointNames = " << JointNames_param_ << std::endl; PCubeParams_->Init(CanModule_, CanDevice_, CanBaudrate_, ModIds_); // get MaxAcc from parameter server ROS_INFO("getting MaxAcc from parameter server"); if (n_.hasParam("MaxAcc")) { n_.getParam("MaxAcc", MaxAcc_param_); } else { ROS_ERROR("Parameter MaxAcc not set"); } MaxAcc_.resize(MaxAcc_param_.size()); for (int i = 0; i<MaxAcc_param_.size(); i++ ) { MaxAcc_[i] = (double)MaxAcc_param_[i]; } PCubeParams_->SetMaxAcc(MaxAcc_); std::cout << "MaxAcc = " << MaxAcc_param_ << std::endl; // load parameter server string for robot/model std::string param_name = "robot_description"; std::string full_param_name; std::string xml_string; n_.searchParam(param_name,full_param_name); n_.getParam(full_param_name.c_str(),xml_string); ROS_INFO("full_param_name=%s",full_param_name.c_str()); if (xml_string.size()==0) { ROS_ERROR("Unable to load robot model from param server robot_description\n"); exit(2); } ROS_DEBUG("%s content\n%s", full_param_name.c_str(), xml_string.c_str()); // extract limits and velocities from urdf model urdf::Model model; if (!model.initString(xml_string)) { ROS_ERROR("Failed to parse urdf file"); exit(2); } ROS_INFO("Successfully parsed urdf file"); /** @todo: check if yaml parameter file fits to urdf model */ // get MaxVel out of urdf model std::vector<double> MaxVel; MaxVel.resize(ModIds_param_.size()); for (int i = 0; i<ModIds_param_.size(); i++ ) { MaxVel[i] = model.getJoint(JointNames_[i].c_str())->limits->velocity; //std::cout << "MaxVel[" << JointNames_[i].c_str() << "] = " << MaxVel[i] << std::endl; } PCubeParams_->SetMaxVel(MaxVel); // get LowerLimits out of urdf model std::vector<double> LowerLimits; LowerLimits.resize(ModIds_param_.size()); for (int i = 0; i<ModIds_param_.size(); i++ ) { LowerLimits[i] = model.getJoint(JointNames_[i].c_str())->limits->lower; std::cout << "LowerLimits[" << JointNames_[i].c_str() << "] = " << LowerLimits[i] << std::endl; } PCubeParams_->SetLowerLimits(LowerLimits); // get UpperLimits out of urdf model std::vector<double> UpperLimits; UpperLimits.resize(ModIds_param_.size()); for (int i = 0; i<ModIds_param_.size(); i++ ) { UpperLimits[i] = model.getJoint(JointNames_[i].c_str())->limits->upper; std::cout << "UpperLimits[" << JointNames_[i].c_str() << "] = " << UpperLimits[i] << std::endl; } PCubeParams_->SetUpperLimits(UpperLimits); // get UpperLimits out of urdf model std::vector<double> Offsets; Offsets.resize(ModIds_param_.size()); for (int i = 0; i<ModIds_param_.size(); i++ ) { Offsets[i] = model.getJoint(JointNames_[i].c_str())->calibration->rising.get()[0]; std::cout << "Offset[" << JointNames_[i].c_str() << "] = " << Offsets[i] << std::endl; } PCubeParams_->SetAngleOffsets(Offsets); cmd_vel_.resize(ModIds_param_.size()); newvel_ = false; can_sem = sem_open("/semcan", O_CREAT, S_IRWXU | S_IRWXG,1); if (can_sem != SEM_FAILED) sem_can_available = true; }
/*! * \brief Gets parameters from the robot_description and configures the powercube_chain. */ void getRobotDescriptionParameters() { unsigned int DOF = pc_params_->GetDOF(); std::vector<std::string> JointNames = pc_params_->GetJointNames(); /// Get robot_description from ROS parameter server std::string param_name = "robot_description"; std::string full_param_name; std::string xml_string; n_.searchParam(param_name, full_param_name); if (n_.hasParam(full_param_name)) { n_.getParam(full_param_name.c_str(), xml_string); } else { ROS_ERROR("Parameter %s not set, shutting down node...", full_param_name.c_str()); n_.shutdown(); } if (xml_string.size() == 0) { ROS_ERROR("Unable to load robot model from parameter %s",full_param_name.c_str()); n_.shutdown(); } ROS_DEBUG("%s content\n%s", full_param_name.c_str(), xml_string.c_str()); /// Get urdf model out of robot_description urdf::Model model; if (!model.initString(xml_string)) { ROS_ERROR("Failed to parse urdf file"); n_.shutdown(); } ROS_DEBUG("Successfully parsed urdf file"); /// Get max velocities out of urdf model std::vector<double> MaxVelocities(DOF); for (unsigned int i = 0; i < DOF; i++) { MaxVelocities[i] = model.getJoint(JointNames[i].c_str())->limits->velocity; } /// Get lower limits out of urdf model std::vector<double> LowerLimits(DOF); for (unsigned int i = 0; i < DOF; i++) { LowerLimits[i] = model.getJoint(JointNames[i].c_str())->limits->lower; } // Get upper limits out of urdf model std::vector<double> UpperLimits(DOF); for (unsigned int i = 0; i < DOF; i++) { UpperLimits[i] = model.getJoint(JointNames[i].c_str())->limits->upper; } /// Get offsets out of urdf model std::vector<double> Offsets(DOF); for (unsigned int i = 0; i < DOF; i++) { Offsets[i] = model.getJoint(JointNames[i].c_str())->calibration->rising.get()[0]; } /// Set parameters pc_params_->SetMaxVel(MaxVelocities); pc_params_->SetLowerLimits(LowerLimits); pc_params_->SetUpperLimits(UpperLimits); pc_params_->SetOffsets(Offsets); }