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 JOINT_RELAY_HANDLER_H
00034 #define JOINT_RELAY_HANDLER_H
00035 
00036 #include <string>
00037 #include <vector>
00038 
00039 #include "ros/ros.h"
00040 #include "control_msgs/FollowJointTrajectoryFeedback.h"
00041 #include "sensor_msgs/JointState.h"
00042 #include "simple_message/message_handler.h"
00043 #include "simple_message/messages/joint_message.h"
00044 #include "trajectory_msgs/JointTrajectoryPoint.h"
00045 
00046 namespace industrial_robot_client
00047 {
00048 namespace joint_relay_handler
00049 {
00050 
00051 using industrial::joint_message::JointMessage;
00052 using industrial::simple_message::SimpleMessage;
00053 using trajectory_msgs::JointTrajectoryPoint;
00054 
00062 class JointRelayHandler : public industrial::message_handler::MessageHandler
00063 {
00064 
00065 public:
00066 
00070   JointRelayHandler() {};
00071 
00072 
00083  virtual bool init(industrial::smpl_msg_connection::SmplMsgConnection* connection, std::vector<std::string> &joint_names)
00084  {
00085    return init(connection, (int)industrial::simple_message::StandardMsgTypes::JOINT, joint_names);
00086  }
00087 
00088 protected:
00089 
00090   std::vector<std::string> all_joint_names_;
00091 
00092   ros::Publisher pub_joint_control_state_;
00093   ros::Publisher pub_joint_sensor_state_;
00094   ros::NodeHandle node_;
00095 
00107   virtual bool init(industrial::smpl_msg_connection::SmplMsgConnection* connection,
00108                     int msg_type, std::vector<std::string> &joint_names);
00109 
00110 
00120   virtual bool create_messages(SimpleMessage& msg_in,
00121                                control_msgs::FollowJointTrajectoryFeedback* control_state,
00122                                sensor_msgs::JointState* sensor_state);
00123 
00130   virtual bool convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state);
00131 
00141   virtual bool transform(const JointTrajectoryPoint& state_in, JointTrajectoryPoint* state_out)
00142   {
00143     *state_out = state_in;  // by default, no transform is applied
00144     return true;
00145   }
00146 
00157   virtual bool select(const JointTrajectoryPoint& all_joint_state, const std::vector<std::string>& all_joint_names,
00158                       JointTrajectoryPoint* pub_joint_state, std::vector<std::string>* pub_joint_names);
00159 
00167   bool internalCB(SimpleMessage& in);
00168 
00169 private:
00176   bool convert_message(JointMessage& msg_in, JointTrajectoryPoint* joint_state);
00177 
00178 };//class JointRelayHandler
00179 
00180 }//joint_relay_handler
00181 }//industrial_robot_cliet
00182 
00183 
00184 #endif /* JOINT_RELAY_HANDLER_H */


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Wed Aug 26 2015 12:37:33