joint_relay_handler.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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 
33 #ifndef JOINT_HANDLER_H
34 #define JOINT_HANDLER_H
35 
36 #include <string>
37 #include <vector>
38 
39 #include "ros/ros.h"
40 #include "control_msgs/FollowJointTrajectoryFeedback.h"
41 #include "sensor_msgs/JointState.h"
44 
45 
47 {
48 namespace joint_relay_handler
49 {
50 
53 
62 {
63  // since this class defines a different init(), this helps find the base-class init()
65 
66 public:
67 
72 
73 
84  bool init(industrial::smpl_msg_connection::SmplMsgConnection* connection, std::vector<std::string> &joint_names);
85 
86 protected:
87 
88  std::vector<std::string> all_joint_names_;
89 
93 
103  virtual bool create_messages(JointMessage& msg_in,
104  control_msgs::FollowJointTrajectoryFeedback* control_state,
105  sensor_msgs::JointState* sensor_state);
106 
116  virtual bool transform(const std::vector<double>& pos_in, std::vector<double>* pos_out)
117  {
118  *pos_out = pos_in; // by default, no transform is applied
119  return true;
120  }
121 
132  virtual bool select(const std::vector<double>& all_joint_pos, const std::vector<std::string>& all_joint_names,
133  std::vector<double>* pub_joint_pos, std::vector<std::string>* pub_joint_names);
134 
142  bool internalCB(JointMessage& in);
143 
144 private:
152  bool internalCB(SimpleMessage& in);
153 };//class JointRelayHandler
154 
155 }//joint_relay_handler
156 }//industrial_robot_cliet
157 
158 
159 #endif /* JOINT_HANDLER_H */
ros::Publisher
industrial::message_handler::MessageHandler
joint_message.h
industrial_robot_client::joint_relay_handler::JointRelayHandler::transform
virtual bool transform(const std::vector< double > &pos_in, std::vector< double > *pos_out)
Transform joint positions before publishing. Can be overridden to implement, e.g. robot-specific join...
Definition: joint_relay_handler.h:116
ros.h
industrial_robot_client::joint_relay_handler::JointRelayHandler::pub_joint_control_state_
ros::Publisher pub_joint_control_state_
Definition: joint_relay_handler.h:90
industrial::message_handler::MessageHandler::init
bool init(int msg_type, industrial::smpl_msg_connection::SmplMsgConnection *connection)
industrial_robot_client::joint_relay_handler::JointRelayHandler::JointRelayHandler
JointRelayHandler()
Constructor.
Definition: joint_relay_handler.h:71
industrial_robot_client::joint_relay_handler::JointRelayHandler::node_
ros::NodeHandle node_
Definition: joint_relay_handler.h:92
industrial_robot_client::joint_relay_handler::JointRelayHandler::create_messages
virtual bool create_messages(JointMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
Convert joint message into publish message-types.
Definition: joint_relay_handler.cpp:98
industrial::simple_message::SimpleMessage
industrial_robot_client::joint_relay_handler::JointRelayHandler::internalCB
bool internalCB(JointMessage &in)
Callback executed upon receiving a joint message.
Definition: joint_relay_handler.cpp:72
industrial::joint_message::JointMessage
industrial::smpl_msg_connection::SmplMsgConnection
industrial_robot_client
Definition: joint_relay_handler.h:46
message_handler.h
industrial_robot_client::joint_relay_handler::JointRelayHandler::all_joint_names_
std::vector< std::string > all_joint_names_
Definition: joint_relay_handler.h:88
industrial_robot_client::joint_relay_handler::JointRelayHandler
Message handler that relays joint positions (converts simple message types to ROS message types and p...
Definition: joint_relay_handler.h:61
industrial_robot_client::joint_relay_handler::JointRelayHandler::pub_joint_sensor_state_
ros::Publisher pub_joint_sensor_state_
Definition: joint_relay_handler.h:91
industrial_robot_client::joint_relay_handler::JointRelayHandler::select
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)
Select specific joints for publishing.
Definition: joint_relay_handler.cpp:146
ros::NodeHandle
industrial_robot_client::joint_relay_handler::JointRelayHandler::init
bool init(industrial::smpl_msg_connection::SmplMsgConnection *connection, std::vector< std::string > &joint_names)
Class initializer.
Definition: joint_relay_handler.cpp:46


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Wed Mar 2 2022 00:24:59