joint_relay_handler.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Southwest Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the Southwest Research Institute, nor the names
16  * of its contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_RELAY_HANDLER_H
33 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_RELAY_HANDLER_H
34 
35 #include <string>
36 #include <vector>
37 #include <map>
38 #include <algorithm>
39 #include "ros/ros.h"
40 #include "control_msgs/FollowJointTrajectoryFeedback.h"
41 #include "sensor_msgs/JointState.h"
44 #include "trajectory_msgs/JointTrajectoryPoint.h"
46 #include "motoman_msgs/DynamicJointsGroup.h"
47 
49 {
50 namespace joint_relay_handler
51 {
52 
55 using trajectory_msgs::JointTrajectoryPoint;
56 using motoman_msgs::DynamicJointsGroup;
64 class JointRelayHandler : public industrial::message_handler::MessageHandler
65 {
66 public:
71 
72  typedef std::map<int, RobotGroup>::iterator it_type;
84  std::map<int, RobotGroup>& robot_groups)
85  {
86  return init(connection, static_cast<int>(industrial::simple_message::StandardMsgTypes::JOINT), robot_groups);
87  }
88 
100  std::vector<std::string>& joint_names)
101  {
102  return init(connection, static_cast<int>(industrial::simple_message::StandardMsgTypes::JOINT), joint_names);
103  }
104 
105 protected:
106  std::vector<std::string> all_joint_names_;
107  std::map<int, RobotGroup> robot_groups_;
108 
112 
113  std::map<int, ros::Publisher> pub_controls_;
114  std::map<int, ros::Publisher> pub_states_;
115 
128  int msg_type, std::vector<std::string> &joint_names);
129 
142  int msg_type, std::map<int, RobotGroup> &robot_groups);
152  virtual bool create_messages(SimpleMessage& msg_in,
153  control_msgs::FollowJointTrajectoryFeedback* control_state,
154  sensor_msgs::JointState* sensor_state);
155 
165  virtual bool create_messages(SimpleMessage& msg_in,
166  control_msgs::FollowJointTrajectoryFeedback* control_state,
167  sensor_msgs::JointState* sensor_state, int robot_id);
168 
175  virtual bool convert_message(SimpleMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
176 
183  virtual bool convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state);
184 
194  virtual bool transform(const JointTrajectoryPoint& state_in, JointTrajectoryPoint* state_out)
195  {
196  *state_out = state_in; // by default, no transform is applied
197  return true;
198  }
199 
209  virtual bool transform(const DynamicJointsGroup& state_in, DynamicJointsGroup* state_out)
210  {
211  *state_out = state_in; // by default, no transform is applied
212  return true;
213  }
214 
215 
226  virtual bool select(const JointTrajectoryPoint& all_joint_state, const std::vector<std::string>& all_joint_names,
227  JointTrajectoryPoint* pub_joint_state, std::vector<std::string>* pub_joint_names);
228 
229  virtual bool select(const DynamicJointsGroup& all_joint_state, const std::vector<std::string>& all_joint_names,
230  DynamicJointsGroup* pub_joint_state, std::vector<std::string>* pub_joint_names);
231 
239  bool internalCB(SimpleMessage& in);
240 
241 private:
248  bool convert_message(JointMessage& msg_in, JointTrajectoryPoint* joint_state);
249 
256  bool convert_message(JointMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
257 }; // class JointRelayHandler
258 
259 } // namespace joint_relay_handler
260 } // namespace industrial_robot_client
261 
262 
263 #endif // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_RELAY_HANDLER_H
bool init(industrial::smpl_msg_connection::SmplMsgConnection *connection, std::vector< std::string > &joint_names)
virtual bool create_messages(JointMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
virtual bool transform(const std::vector< double > &pos_in, std::vector< double > *pos_out)
virtual bool select(const std::vector< double > &all_joint_pos, const std::vector< std::string > &all_joint_names, std::vector< double > *pub_joint_pos, std::vector< std::string > *pub_joint_names)


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute), Ted Miller (MotoROS) (Yaskawa Motoman), Eric Marcil (MotoROS) (Yaskawa Motoman)
autogenerated on Sat May 8 2021 02:27:43