wrench_relay_handler.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * FSRobo-R Package BSDL
3 * ---------
4 * Copyright (C) 2019 FUJISOFT. All rights reserved.
5 *
6 * Redistribution and use in source and binary forms, with or without modification,
7 * are permitted provided that the following conditions are met:
8 * 1. Redistributions of source code must retain the above copyright notice,
9 * this list of conditions and the following disclaimer.
10 * 2. Redistributions in binary form must reproduce the above copyright notice,
11 * this list of conditions and the following disclaimer in the documentation and/or
12 * other materials provided with the distribution.
13 * 3. Neither the name of the copyright holder nor the names of its contributors
14 * may be used to endorse or promote products derived from this software without
15 * specific prior written permission.
16 *
17 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
20 * IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
21 * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
25 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 *********************************************************************/
28 
30 #include "geometry_msgs/WrenchStamped.h"
32 #include <sstream>
33 
34 using namespace industrial::shared_types;
35 using namespace industrial::smpl_msg_connection;
36 using namespace industrial::simple_message;
39 
40 namespace fsrobo_r_driver
41 {
42 namespace wrench_relay_handler
43 {
44 
45 bool WrenchRelayHandler::init(SmplMsgConnection *connection)
46 {
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");
50  return init((int)fsrobo_r_driver::simple_message::FSRoboRMsgType::WRENCH, connection);
51 }
52 
53 bool WrenchRelayHandler::internalCB(SimpleMessage &in)
54 {
55  WrenchMessage wrench_msg;
56 
57  if (!wrench_msg.init(in))
58  {
59  LOG_ERROR("Failed to initialize wrench message");
60  return false;
61  }
62 
63  return internalCB(wrench_msg);
64 }
65 
66 bool WrenchRelayHandler::internalCB(WrenchMessage &in)
67 {
68  geometry_msgs::WrenchStamped wrench_stamped;
69  bool rtn = true;
70 
71  // ROS_WARN("%f %f %f %f %f %f", in.wrench_.getForce(0), in.wrench_.getForce(1), in.wrench_.getForce(2),
72  // in.wrench_.getTorque(0), in.wrench_.getTorque(1), in.wrench_.getTorque(2));
73 
74  wrench_stamped.header.stamp = ros::Time::now();
75  wrench_stamped.header.frame_id = force_frame_id_;
76  wrench_stamped.wrench.force.x = in.wrench_.getForce(0);
77  wrench_stamped.wrench.force.y = in.wrench_.getForce(1);
78  wrench_stamped.wrench.force.z = in.wrench_.getForce(2);
79  wrench_stamped.wrench.torque.x = in.wrench_.getTorque(0);
80  wrench_stamped.wrench.torque.y = in.wrench_.getTorque(1);
81  wrench_stamped.wrench.torque.z = in.wrench_.getTorque(2);
82  this->pub_wrench_stamped_.publish(wrench_stamped);
83 
84  // Reply back to the controller if the sender requested it.
85  if (CommTypes::SERVICE_REQUEST == in.getCommType())
86  {
87  SimpleMessage reply;
88  in.toReply(reply, rtn ? ReplyTypes::SUCCESS : ReplyTypes::FAILURE);
89  this->getConnection()->sendMsg(reply);
90  }
91 
92  return rtn;
93 }
94 
95 }
96 }
97 
bool init(industrial::simple_message::SimpleMessage &msg)
Initializes message from a simple message.
fsrobo_r_driver::simple_message::wrench::Wrench wrench_
#define ROS_WARN(...)
#define LOG_ERROR(format,...)
industrial::shared_types::shared_real getForce(int idx)
Initializes a full robot status message.
Definition: wrench.h:100
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...
static Time now()
industrial::shared_types::shared_real getTorque(int idx)
Definition: wrench.h:105


fsrobo_r_driver
Author(s): F-ROSROBO
autogenerated on Sun Feb 9 2020 03:58:29