joint_feedback_ex_relay_handler.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, Fraunhofer IPA
5  * Author: Thiago de Freitas
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above copyright
15  * notice, this list of conditions and the following disclaimer in the
16  * documentation and/or other materials provided with the distribution.
17  * * Neither the name of the Fraunhofer IPA, nor the names
18  * of its contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H
35 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H
36 
37 #include <vector>
38 #include <map>
39 #include <string>
43 #include "motoman_msgs/DynamicJointsGroup.h"
44 #include "motoman_msgs/DynamicJointTrajectoryFeedback.h"
45 
47 {
48 namespace joint_feedback_ex_relay_handler
49 {
50 
57 using trajectory_msgs::JointTrajectoryPoint;
58 using motoman_msgs::DynamicJointsGroup;
59 using motoman_msgs::DynamicJointTrajectoryFeedback;
60 
69 {
70 public:
74  explicit JointFeedbackExRelayHandler(int groups_number = -1) : groups_number_(groups_number) {}
75 
76 
87  virtual bool init(SmplMsgConnection* connection,
88  std::vector<std::string> &joint_names);
89 
90  virtual bool init(SmplMsgConnection* connection,
91  std::map<int, RobotGroup> &robot_groups);
92 
93 protected:
95  bool version_0_;
96 
100 
109  virtual bool convert_message(JointFeedbackMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
110 
111  // override JointRelayHandler::create_messages, to check robot_id w/o error msg
112  bool create_messages(SimpleMessage& msg_in,
113  control_msgs::FollowJointTrajectoryFeedback* control_state,
114  sensor_msgs::JointState* sensor_state);
115 
116  // override JointRelayHandler::create_messages, to check robot_id w/o error msg
118  control_msgs::FollowJointTrajectoryFeedback* control_state,
119  sensor_msgs::JointState* sensor_state, int robot_id);
120 
121 private:
122  static bool JointDataToVector(const industrial::joint_data::JointData &joints,
123  std::vector<double> &vec, int len);
124 
125 
131 
138  bool convert_message(JointFeedbackExMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
139 }; // class JointFeedbackExRelayHandler
140 
141 } // namespace joint_feedback_ex_relay_handler
142 } // namespace industrial_robot_client
143 
144 #endif // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H
Message handler that relays joint positions (converts simple message types to ROS message types and p...
virtual bool init(SmplMsgConnection *connection, std::vector< std::string > &joint_names)
Class initializer.
Class encapsulated joint feedback ex message generation methods (either to or from a industrial::simp...
virtual bool convert_message(JointFeedbackMessage &msg_in, DynamicJointsGroup *joint_state, int robot_id)
Convert joint message into intermediate message-type.
static bool JointDataToVector(const industrial::joint_data::JointData &joints, std::vector< double > &vec, int len)
industrial::shared_types::shared_int valid_fields_from_message_
bit-mask of (optional) fields that have been initialized with valid data
bool create_messages(SimpleMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
Convert joint message into publish message-types.
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