30 #include <std_msgs/String.h> 31 #include <std_msgs/Float64MultiArray.h> 32 #include <sensor_msgs/JointState.h> 33 #include <trajectory_msgs/JointTrajectory.h> 34 #include <control_msgs/JointTrajectoryControllerState.h> 35 #include <diagnostic_msgs/DiagnosticArray.h> 38 #include <std_srvs/Trigger.h> 39 #include <cob_srvs/SetString.h> 96 topicPub_JointState_ = n_.
advertise<sensor_msgs::JointState>(
"joint_states", 1);
97 topicPub_ControllerState_ = n_.
advertise<control_msgs::JointTrajectoryControllerState>(
"joint_trajectory_controller/state", 1);
98 topicPub_Diagnostic_ = n_.
advertise<diagnostic_msgs::DiagnosticArray>(
"diagnostics", 1);
109 topicPub_OperationMode_ = n_.
advertise<std_msgs::String>(
"driver/current_operationmode", 1);
111 initialized_ =
false;
120 bool closed = pc_ctrl_->
Close();
122 ROS_INFO(
"PowerCube Device closed!");
131 std::string CanModule;
132 if (n_private_.
hasParam(
"can_module"))
134 n_private_.
getParam(
"can_module", CanModule);
138 ROS_ERROR(
"Parameter can_module not set, shutting down node...");
143 std::string CanDevice;
144 if (n_private_.
hasParam(
"can_device"))
146 n_private_.
getParam(
"can_device", CanDevice);
150 ROS_ERROR(
"Parameter can_device not set, shutting down node...");
156 if (n_private_.
hasParam(
"can_baudrate"))
158 n_private_.
getParam(
"can_baudrate", CanBaudrate);
162 ROS_ERROR(
"Parameter can_baudrate not set, shutting down node...");
168 std::vector<int> ModulIDs;
169 if (n_private_.
hasParam(
"modul_ids"))
171 n_private_.
getParam(
"modul_ids", ModulIDsXmlRpc);
175 ROS_ERROR(
"Parameter modul_ids not set, shutting down node...");
181 if (n_private_.
hasParam(
"force_use_movevel"))
183 n_private_.
getParam(
"force_use_movevel", UseMoveVel);
184 ROS_INFO(
"Parameter force_use_movevel set, using moveVel");
188 ROS_INFO(
"Parameter force_use_movevel not set, using moveStep");
194 ModulIDs.resize(ModulIDsXmlRpc.
size());
195 for (
int i = 0; i < ModulIDsXmlRpc.
size(); i++)
197 ModulIDs[i] = (int)ModulIDsXmlRpc[i];
201 pc_params_->
Init(CanModule, CanDevice, CanBaudrate, ModulIDs);
205 std::vector<std::string> JointNames;
206 if (n_private_.
hasParam(
"joint_names"))
208 n_private_.
getParam(
"joint_names", JointNamesXmlRpc);
212 ROS_ERROR(
"Parameter joint_names not set, shutting down node...");
217 JointNames.resize(JointNamesXmlRpc.
size());
218 for (
int i = 0; i < JointNamesXmlRpc.
size(); i++)
220 JointNames[i] = (std::string)JointNamesXmlRpc[i];
224 if ((
int)JointNames.size() != pc_params_->
GetDOF())
226 ROS_ERROR(
"Wrong dimensions of parameter joint_names, shutting down node...");
233 std::vector<double> MaxAccelerations;
234 if (n_private_.
hasParam(
"max_accelerations"))
236 n_private_.
getParam(
"max_accelerations", MaxAccelerationsXmlRpc);
240 ROS_ERROR(
"Parameter max_accelerations not set, shutting down node...");
245 MaxAccelerations.resize(MaxAccelerationsXmlRpc.
size());
246 for (
int i = 0; i < MaxAccelerationsXmlRpc.
size(); i++)
248 MaxAccelerations[i] = (double)MaxAccelerationsXmlRpc[i];
252 if ((
int)MaxAccelerations.size() != pc_params_->
GetDOF())
254 ROS_ERROR(
"Wrong dimensions of parameter max_accelerations, shutting down node...");
263 n_private_.
getParam(
"horizon", Horizon);
269 ROS_WARN(
"Parameter horizon not available, setting to default value: %f sec", Horizon);
279 unsigned int DOF = pc_params_->
GetDOF();
280 std::vector<std::string> JointNames = pc_params_->
GetJointNames();
283 std::string xml_string;
284 if (n_.
hasParam(
"/robot_description"))
286 n_.
getParam(
"/robot_description", xml_string);
290 ROS_ERROR(
"Parameter '/robot_description' not set, shutting down node...");
294 if (xml_string.size() == 0)
296 ROS_ERROR(
"Unable to load robot model from parameter /robot_description'");
307 ROS_DEBUG(
"Successfully parsed urdf file");
310 std::vector<double> MaxVelocities(DOF);
311 for (
unsigned int i = 0; i < DOF; i++)
313 MaxVelocities[i] = model.getJoint(JointNames[i].c_str())->limits->velocity;
317 std::vector<double> LowerLimits(DOF);
318 for (
unsigned int i = 0; i < DOF; i++)
320 LowerLimits[i] = model.getJoint(JointNames[i].c_str())->limits->lower;
324 std::vector<double> UpperLimits(DOF);
325 for (
unsigned int i = 0; i < DOF; i++)
327 UpperLimits[i] = model.getJoint(JointNames[i].c_str())->limits->upper;
331 std::vector<double> Offsets(DOF);
332 for (
unsigned int i = 0; i < DOF; i++)
334 if(model.getJoint(JointNames[i].c_str())->calibration == NULL)
337 Offsets[i] = model.getJoint(JointNames[i].c_str())->calibration->rising.get()[0];
355 ROS_DEBUG(
"Received new position command");
358 ROS_WARN(
"Skipping command: powercubes not initialized");
370 std::vector<std::string> errorMessages;
371 pc_ctrl_->
getStatus(status, errorMessages);
374 if (msg->data.size() != pc_params_->
GetDOF())
376 ROS_ERROR(
"Skipping command: Commanded positionss and DOF are not same dimension.");
402 ROS_DEBUG(
"Received new velocity command");
405 ROS_WARN(
"Skipping command: powercubes not initialized");
417 std::vector<std::string> errorMessages;
418 pc_ctrl_->
getStatus(status, errorMessages);
420 unsigned int DOF = pc_params_->
GetDOF();
423 if (msg->data.size() != DOF)
425 ROS_ERROR(
"Skipping command: Commanded velocities and DOF are not same dimension.");
430 if (!pc_ctrl_->
MoveVel(msg->data))
454 ROS_INFO(
"Initializing powercubes...");
457 if (pc_ctrl_->
Init(pc_params_))
461 ROS_INFO(
"...initializing powercubes successful");
470 ROS_INFO(
"...initializing powercubes not successful. error: %s", res.message.c_str());
477 res.message =
"powercubes already initialized";
478 ROS_WARN(
"...initializing powercubes not successful. error: %s", res.message.c_str());
496 if (pc_ctrl_->
Stop())
499 ROS_INFO(
"...stopping powercubes successful.");
506 ROS_ERROR(
"...stopping powercubes not successful. error: %s", res.message.c_str());
520 ROS_INFO(
"Recovering powercubes...");
529 ROS_INFO(
"...recovering powercubes successful.");
537 ROS_ERROR(
"...recovering powercubes not successful. error: %s", res.message.c_str());
543 res.message =
"powercubes not initialized";
544 ROS_ERROR(
"...recovering powercubes not successful. error: %s", res.message.c_str());
559 if (req.data !=
"velocity")
561 ROS_WARN(
"Powercube chain currently only supports velocity commands");
588 sensor_msgs::JointState joint_state_msg;
593 joint_state_msg.effort.resize(pc_params_->
GetDOF());
595 control_msgs::JointTrajectoryControllerState controller_state_msg;
596 controller_state_msg.header.stamp = joint_state_msg.header.stamp;
597 controller_state_msg.joint_names = pc_params_->
GetJointNames();
598 controller_state_msg.actual.positions = pc_ctrl_->
getPositions();
599 controller_state_msg.actual.velocities = pc_ctrl_->
getVelocities();
602 std_msgs::String opmode_msg;
603 opmode_msg.data =
"velocity";
606 topicPub_JointState_.
publish(joint_state_msg);
607 topicPub_ControllerState_.
publish(controller_state_msg);
608 topicPub_OperationMode_.
publish(opmode_msg);
610 last_publish_time_ = joint_state_msg.header.stamp;
630 diagnostic_msgs::DiagnosticArray diagnostics;
631 diagnostics.status.resize(1);
636 diagnostics.status[0].level = 2;
644 diagnostics.status[0].level = 0;
646 diagnostics.status[0].message =
"powercubechain initialized and running";
650 diagnostics.status[0].level = 1;
652 diagnostics.status[0].message =
"powercubechain not initialized";
656 topicPub_Diagnostic_.
publish(diagnostics);
665 int main(
int argc,
char **argv)
668 ros::init(argc, argv,
"powercube_chain");
686 ROS_WARN(
"Parameter 'frequency' not available, setting to default value: %f Hz", frequency);
694 min_publish_duration.
fromSec(sec);
698 ROS_ERROR(
"Parameter 'min_publish_time' not available");
702 if ((1.0 / min_publish_duration.
toSec()) > frequency)
704 ROS_ERROR(
"min_publish_duration has to be longer then delta_t of controller frequency!");
710 while (pc_node.
n_.
ok())
bool setHorizon(double horizon)
Sets the horizon (sec).
std::vector< double > getPositions()
Gets the current positions.
std::vector< std::string > GetJointNames()
Gets the joint names.
bool srvCallback_Recover(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for recover.
void publish(const boost::shared_ptr< M > &message) const
URDF_EXPORT bool initString(const std::string &xmlstring)
Implementation of ROS node for powercube_chain.
~PowerCubeChainNode()
Destructor.
int SetLowerLimits(std::vector< double > LowerLimits)
Sets the lower angular limits (rad) for the joints.
ros::ServiceServer srvServer_Recover_
PowerCubeChainNode()
Constructor.
int main(int argc, char **argv)
Main loop of ROS node.
PowerCubeCtrl * pc_ctrl_
handle for powercube_chain
bool MoveVel(const std::vector< double > &velocities)
Moves all cubes by the given velocities.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getRobotDescriptionParameters()
Gets parameters from the robot_description and configures the powercube_chain.
void getROSParameters()
Gets parameters from the ROS parameter server and configures the powercube_chain. ...
PowerCubeCtrlParams * pc_params_
handle for powercube_chain parameters
ros::Time last_publish_time_
bool getStatus(PC_CTRL_STATUS &status, std::vector< std::string > &errorMessages)
Gets the status of the modules.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int SetOffsets(std::vector< double > AngleOffsets)
Sets the offset angulars (rad) for the joints.
ros::Subscriber topicSub_CommandVel_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::Publisher topicPub_JointState_
declaration of topics to publish
void SetUseMoveVel(bool UseMoveVel)
Sets UseMoveVel.
ros::ServiceServer srvServer_Stop_
ros::Publisher topicPub_Diagnostic_
int SetJointNames(std::vector< std::string > JointNames)
Sets the joint names.
bool Init(PowerCubeCtrlParams *params)
Initializing.
bool Recover()
Recovery after emergency stop or power supply failure.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void publishState(bool update=true)
Publishes the state of the powercube_chain as ros messages.
std::vector< double > getAccelerations()
Gets the current accelerations.
bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
Executes the service callback for SetOperationMode.
std::vector< double > getVelocities()
Gets the current velcities.
Duration & fromSec(double t)
PC_CTRL_STATUS getPC_Status() const
Get PC_Status message.
void topicCallback_CommandPos(const std_msgs::Float64MultiArray::ConstPtr &msg)
Executes the callback from the command_pos topic.
int SetUpperLimits(std::vector< double > UpperLimits)
Sets the upper angular limits (rad) for the joints.
ros::NodeHandle n_private_
bool initialized_
member variables
const std::string & getNamespace() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int GetDOF()
Gets the DOF value.
ros::Publisher topicPub_OperationMode_
int SetMaxAcc(std::vector< double > MaxAcc)
Sets the max. angular accelerations (rad/s^2) for the joints.
bool srvCallback_Init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for init.
ros::ServiceServer srvServer_SetOperationMode_
ros::NodeHandle n_
create a handle for this node, initialize node
bool updateStates()
Returns the state of all modules.
int SetMaxVel(std::vector< double > MaxVel)
Sets the max. angular velocities (rad/s) for the joints.
ros::ServiceServer srvServer_Init_
declaration of service servers
ros::Subscriber topicSub_CommandPos_
declaration of topics to subscribe, callback is called for new messages arriving
bool getParam(const std::string &key, std::string &s) const
int Init(std::string CanModule, std::string CanDevice, int Baudrate, std::vector< int > ModuleIDs)
Initializing.
bool srvCallback_Stop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for stop.
std::string getErrorMessage() const
Get error message.
void topicCallback_CommandVel(const std_msgs::Float64MultiArray::ConstPtr &msg)
Executes the callback from the command_vel topic.
bool Stop()
Stops the Manipulator immediately.
bool hasParam(const std::string &key) const
ROSCPP_DECL void spinOnce()
Parameters for cob_powercube_chain.
bool MoveJointSpaceSync(const std::vector< double > &angles)
Send position goals to powercubes, the final angles will be reached simultaneously.
ros::Publisher topicPub_ControllerState_