joint_feedback_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_FEEDBACK_RELAY_HANDLER_H
33 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_RELAY_HANDLER_H
34 
35 #include <algorithm>
36 #include <map>
37 #include <string>
38 #include <vector>
41 #include "motoman_msgs/DynamicJointsGroup.h"
42 
44 {
45 namespace joint_feedback_relay_handler
46 {
47 
52 using trajectory_msgs::JointTrajectoryPoint;
53 using motoman_msgs::DynamicJointsGroup;
54 
63 {
64 public:
68  explicit JointFeedbackRelayHandler(int robot_id = -1) : robot_id_(robot_id) {}
69 
70 
81  virtual bool init(SmplMsgConnection* connection,
82  std::vector<std::string> &joint_names);
83 
84  virtual bool init(SmplMsgConnection* connection,
85  std::map<int, RobotGroup> &robot_groups);
86 
87 protected:
88  int robot_id_;
89  bool version_0_;
90 
91 
98  virtual bool convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state);
99 
106  virtual bool convert_message(SimpleMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
107 
108  // override JointRelayHandler::create_messages, to check robot_id w/o error msg
109  bool create_messages(SimpleMessage& msg_in,
110  control_msgs::FollowJointTrajectoryFeedback* control_state,
111  sensor_msgs::JointState* sensor_state);
112 
113  bool create_messages(SimpleMessage& msg_in,
114  control_msgs::FollowJointTrajectoryFeedback* control_state,
115  sensor_msgs::JointState* sensor_state, int robot_id);
116 
117  // Overriding some functions to get it to work now inside of the Motoman package
118  virtual bool transform(const DynamicJointsGroup& state_in, DynamicJointsGroup* state_out)
119  {
120  *state_out = state_in; // by default, no transform is applied
121  return true;
122  }
123 
124  virtual bool select(const DynamicJointsGroup& all_joint_state, const std::vector<std::string>& all_joint_names,
125  DynamicJointsGroup* pub_joint_state, std::vector<std::string>* pub_joint_names);
126 
127 private:
128  static bool JointDataToVector(const industrial::joint_data::JointData &joints,
129  std::vector<double> &vec, int len);
130 
137  bool convert_message(JointFeedbackMessage& msg_in, JointTrajectoryPoint* joint_state);
138 
145  bool convert_message(JointFeedbackMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
146 }; // class JointFeedbackRelayHandler
147 
148 } // namespace joint_feedback_relay_handler
149 } // namespace industrial_robot_client
150 
151 
152 #endif // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_RELAY_HANDLER_H
virtual bool transform(const DynamicJointsGroup &state_in, DynamicJointsGroup *state_out)
Transform joint state before publishing. Can be overridden to implement, e.g. robot-specific joint co...
bool create_messages(SimpleMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
Convert joint message into publish message-types.
virtual bool convert_message(SimpleMessage &msg_in, JointTrajectoryPoint *joint_state)
Convert joint message into intermediate message-type.
static bool JointDataToVector(const industrial::joint_data::JointData &joints, std::vector< double > &vec, int len)
virtual bool select(const DynamicJointsGroup &all_joint_state, const std::vector< std::string > &all_joint_names, DynamicJointsGroup *pub_joint_state, std::vector< std::string > *pub_joint_names)
virtual bool init(SmplMsgConnection *connection, std::vector< std::string > &joint_names)
Class initializer.
Message handler that relays joint positions (converts simple message types to ROS message types and p...
Message handler that relays joint positions (converts simple message types to ROS message types and p...


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