30 #include "geometry_msgs/WrenchStamped.h" 42 namespace wrench_relay_handler
47 ROS_WARN(
"WrenchRelayHandler::init!");
48 this->pub_wrench_stamped_ = this->node_.advertise<geometry_msgs::WrenchStamped>(
"raw_force", 1);
49 ros::param::param<std::string>(
"frame_id", force_frame_id_,
"/sensor");
57 if (!wrench_msg.
init(in))
59 LOG_ERROR(
"Failed to initialize wrench message");
63 return internalCB(wrench_msg);
68 geometry_msgs::WrenchStamped wrench_stamped;
75 wrench_stamped.header.frame_id = force_frame_id_;
82 this->pub_wrench_stamped_.publish(wrench_stamped);
88 in.
toReply(reply, rtn ? ReplyTypes::SUCCESS : ReplyTypes::FAILURE);
89 this->getConnection()->sendMsg(reply);
bool init(industrial::simple_message::SimpleMessage &msg)
Initializes message from a simple message.
fsrobo_r_driver::simple_message::wrench::Wrench wrench_
#define LOG_ERROR(format,...)
industrial::shared_types::shared_real getForce(int idx)
Initializes a full robot status message.
virtual bool toReply(industrial::simple_message::SimpleMessage &msg, industrial::simple_message::ReplyType reply)
Class encapsulated robot status message generation methods (either to or from a industrial::simple_me...
industrial::shared_types::shared_real getTorque(int idx)