joint_feedback_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_FEEDBACK_RELAY_HANDLER_H
00034 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_RELAY_HANDLER_H
00035 
00036 #include <map>
00037 #include <string>
00038 #include <vector>
00039 #include "motoman_driver/industrial_robot_client/joint_relay_handler.h"
00040 #include "simple_message/messages/joint_feedback_message.h"
00041 #include "motoman_msgs/DynamicJointsGroup.h"
00042 
00043 namespace industrial_robot_client
00044 {
00045 namespace joint_feedback_relay_handler
00046 {
00047 
00048 using industrial::joint_feedback_message::JointFeedbackMessage;
00049 using industrial::simple_message::SimpleMessage;
00050 using industrial::smpl_msg_connection::SmplMsgConnection;
00051 using industrial_robot_client::joint_relay_handler::JointRelayHandler;
00052 using trajectory_msgs::JointTrajectoryPoint;
00053 using motoman_msgs::DynamicJointsGroup;
00054 
00062 class JointFeedbackRelayHandler : public industrial_robot_client::joint_relay_handler::JointRelayHandler
00063 {
00064 public:
00068   JointFeedbackRelayHandler(int robot_id = -1) : robot_id_(robot_id) {};
00069 
00070 
00081   virtual bool init(SmplMsgConnection* connection,
00082                     std::vector<std::string> &joint_names);
00083 
00084   virtual bool init(SmplMsgConnection* connection,
00085                     std::map<int, RobotGroup> &robot_groups);
00086 
00087 protected:
00088   int robot_id_;
00089   bool version_0_;
00090 
00091 
00098   virtual bool convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state);
00099 
00106   virtual bool convert_message(SimpleMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00107 
00108   // override JointRelayHandler::create_messages, to check robot_id w/o error msg
00109   bool create_messages(SimpleMessage& msg_in,
00110                        control_msgs::FollowJointTrajectoryFeedback* control_state,
00111                        sensor_msgs::JointState* sensor_state);
00112 
00113   bool create_messages(SimpleMessage& msg_in,
00114                        control_msgs::FollowJointTrajectoryFeedback* control_state,
00115                        sensor_msgs::JointState* sensor_state, int robot_id);
00116 
00117   // Overriding some functions to get it to work now inside of the Motoman package
00118   virtual bool transform(const DynamicJointsGroup& state_in, DynamicJointsGroup* state_out)
00119   {
00120     *state_out = state_in;  // by default, no transform is applied
00121     return true;
00122   }
00123 
00124   virtual bool select(const DynamicJointsGroup& all_joint_state, const std::vector<std::string>& all_joint_names,
00125                       DynamicJointsGroup* pub_joint_state, std::vector<std::string>* pub_joint_names);
00126 
00127 private:
00128   static bool JointDataToVector(const industrial::joint_data::JointData &joints,
00129                                 std::vector<double> &vec, int len);
00130 
00137   bool convert_message(JointFeedbackMessage& msg_in, JointTrajectoryPoint* joint_state);
00138 
00145   bool convert_message(JointFeedbackMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00146 };  // class JointFeedbackRelayHandler
00147 
00148 }  // namespace joint_feedback_relay_handler
00149 }  // namespace industrial_robot_cliet
00150 
00151 
00152 #endif  // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_RELAY_HANDLER_H


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