joint_relay_handler.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2013, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *       * Redistributions of source code must retain the above copyright
00011  *       notice, this list of conditions and the following disclaimer.
00012  *       * Redistributions in binary form must reproduce the above copyright
00013  *       notice, this list of conditions and the following disclaimer in the
00014  *       documentation and/or other materials provided with the distribution.
00015  *       * Neither the name of the Southwest Research Institute, nor the names
00016  *       of its contributors may be used to endorse or promote products derived
00017  *       from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 
00033 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_RELAY_HANDLER_H
00034 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_RELAY_HANDLER_H
00035 
00036 #include <string>
00037 #include <vector>
00038 #include <map>
00039 #include <algorithm>
00040 #include "ros/ros.h"
00041 #include "control_msgs/FollowJointTrajectoryFeedback.h"
00042 #include "sensor_msgs/JointState.h"
00043 #include "simple_message/message_handler.h"
00044 #include "simple_message/messages/joint_message.h"
00045 #include "trajectory_msgs/JointTrajectoryPoint.h"
00046 #include "motoman_driver/industrial_robot_client/robot_group.h"
00047 #include "motoman_msgs/DynamicJointsGroup.h"
00048 
00049 namespace industrial_robot_client
00050 {
00051 namespace joint_relay_handler
00052 {
00053 
00054 using industrial::joint_message::JointMessage;
00055 using industrial::simple_message::SimpleMessage;
00056 using trajectory_msgs::JointTrajectoryPoint;
00057 using motoman_msgs::DynamicJointsGroup;
00065 class JointRelayHandler : public industrial::message_handler::MessageHandler
00066 {
00067 public:
00068 
00072   JointRelayHandler() {};
00073 
00074   typedef std::map<int, RobotGroup>::iterator it_type;
00085   virtual bool init(industrial::smpl_msg_connection::SmplMsgConnection* connection, std::map<int, RobotGroup> &robot_groups)
00086   {
00087     return init(connection, static_cast<int>(industrial::simple_message::StandardMsgTypes::JOINT), robot_groups);
00088   }
00089 
00100   virtual bool init(industrial::smpl_msg_connection::SmplMsgConnection* connection, std::vector<std::string> &joint_names)
00101   {
00102     return init(connection, static_cast<int>(industrial::simple_message::StandardMsgTypes::JOINT), joint_names);
00103   }
00104 
00105 protected:
00106   std::vector<std::string> all_joint_names_;
00107   std::map<int, RobotGroup> robot_groups_;
00108 
00109   ros::Publisher pub_joint_control_state_;
00110   ros::Publisher pub_joint_sensor_state_;
00111   ros::NodeHandle node_;
00112 
00113   std::map<int, ros::Publisher> pub_controls_;
00114   std::map<int, ros::Publisher> pub_states_;
00115 
00127   virtual bool init(industrial::smpl_msg_connection::SmplMsgConnection* connection,
00128                     int msg_type, std::vector<std::string> &joint_names);
00129 
00141   virtual bool init(industrial::smpl_msg_connection::SmplMsgConnection* connection,
00142                     int msg_type, std::map<int, RobotGroup> &robot_groups);
00152   virtual bool create_messages(SimpleMessage& msg_in,
00153                                control_msgs::FollowJointTrajectoryFeedback* control_state,
00154                                sensor_msgs::JointState* sensor_state);
00155 
00165   virtual bool create_messages(SimpleMessage& msg_in,
00166                                control_msgs::FollowJointTrajectoryFeedback* control_state,
00167                                sensor_msgs::JointState* sensor_state, int robot_id);
00168 
00175   virtual bool convert_message(SimpleMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00176 
00183   virtual bool convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state);
00184 
00194   virtual bool transform(const JointTrajectoryPoint& state_in, JointTrajectoryPoint* state_out)
00195   {
00196     *state_out = state_in;  // by default, no transform is applied
00197     return true;
00198   }
00199 
00209   virtual bool transform(const DynamicJointsGroup& state_in, DynamicJointsGroup* state_out)
00210   {
00211     *state_out = state_in;  // by default, no transform is applied
00212     return true;
00213   }
00214 
00215 
00226   virtual bool select(const JointTrajectoryPoint& all_joint_state, const std::vector<std::string>& all_joint_names,
00227                       JointTrajectoryPoint* pub_joint_state, std::vector<std::string>* pub_joint_names);
00228 
00229   virtual bool select(const DynamicJointsGroup& all_joint_state, const std::vector<std::string>& all_joint_names,
00230                       DynamicJointsGroup* pub_joint_state, std::vector<std::string>* pub_joint_names);
00231 
00239   bool internalCB(SimpleMessage& in);
00240 
00241 private:
00248   bool convert_message(JointMessage& msg_in, JointTrajectoryPoint* joint_state);
00249 
00256   bool convert_message(JointMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00257 
00258 };  // class JointRelayHandler
00259 
00260 }  // namespace joint_relay_handler
00261 }  // namespace industrial_robot_cliet
00262 
00263 
00264 #endif  // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_RELAY_HANDLER_H


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Sat Jun 8 2019 19:06:57