joint_feedback_ex_relay_handler.h
Go to the documentation of this file.
00001 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H
00002 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H
00003 
00004 #include <vector>
00005 #include <map>
00006 #include <string>
00007 #include "motoman_driver/industrial_robot_client/joint_relay_handler.h"
00008 /*
00009  * Software License Agreement (BSD License)
00010  *
00011  * Copyright (c) 2014, Fraunhofer IPA
00012  * Author: Thiago de Freitas
00013  *
00014  * All rights reserved.
00015  *
00016  * Redistribution and use in source and binary forms, with or without
00017  * modification, are permitted provided that the following conditions are met:
00018  *
00019  *  * Redistributions of source code must retain the above copyright
00020  *  notice, this list of conditions and the following disclaimer.
00021  *  * Redistributions in binary form must reproduce the above copyright
00022  *  notice, this list of conditions and the following disclaimer in the
00023  *  documentation and/or other materials provided with the distribution.
00024  *  * Neither the name of the Fraunhofer IPA, nor the names
00025  *  of its contributors may be used to endorse or promote products derived
00026  *  from this software without specific prior written permission.
00027  *
00028  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00029  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00030  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00031  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00032  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00033  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00034  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00035  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00036  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00037  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00038  * POSSIBILITY OF SUCH DAMAGE.
00039  */
00040 
00041 #include "motoman_driver/industrial_robot_client/joint_feedback_relay_handler.h"
00042 #include "motoman_driver/simple_message/messages/joint_feedback_ex_message.h"
00043 #include "motoman_msgs/DynamicJointsGroup.h"
00044 #include "motoman_msgs/DynamicJointTrajectoryFeedback.h"
00045 
00046 namespace industrial_robot_client
00047 {
00048 namespace joint_feedback_ex_relay_handler
00049 {
00050 
00051 using industrial::joint_feedback_ex_message::JointFeedbackExMessage;
00052 using industrial::joint_feedback_message::JointFeedbackMessage;
00053 using industrial::simple_message::SimpleMessage;
00054 using industrial::smpl_msg_connection::SmplMsgConnection;
00055 using industrial_robot_client::joint_relay_handler::JointRelayHandler;
00056 using industrial_robot_client::joint_feedback_relay_handler::JointFeedbackRelayHandler;
00057 using trajectory_msgs::JointTrajectoryPoint;
00058 using motoman_msgs::DynamicJointsGroup;
00059 using motoman_msgs::DynamicJointTrajectoryFeedback;
00060 
00068 class JointFeedbackExRelayHandler : public industrial_robot_client::joint_relay_handler::JointRelayHandler
00069 {
00070 public:
00074   JointFeedbackExRelayHandler(int groups_number = -1) : groups_number_(groups_number) {};
00075 
00076 
00087   virtual bool init(SmplMsgConnection* connection,
00088                     std::vector<std::string> &joint_names);
00089 
00090   virtual bool init(SmplMsgConnection* connection,
00091                     std::map<int, RobotGroup> &robot_groups);
00092 
00093 protected:
00094   int groups_number_;
00095   bool version_0_;
00096 
00097   ros::Publisher pub_joint_control_state_;
00098   ros::Publisher dynamic_pub_joint_control_state_;
00099   ros::Publisher pub_joint_sensor_state_;
00100 
00109   virtual bool convert_message(JointFeedbackMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00110 
00111   // override JointRelayHandler::create_messages, to check robot_id w/o error msg
00112   bool create_messages(SimpleMessage& msg_in,
00113                        control_msgs::FollowJointTrajectoryFeedback* control_state,
00114                        sensor_msgs::JointState* sensor_state);
00115 
00116   // override JointRelayHandler::create_messages, to check robot_id w/o error msg
00117   bool create_messages(JointFeedbackMessage& msg_in,
00118                        control_msgs::FollowJointTrajectoryFeedback* control_state,
00119                        sensor_msgs::JointState* sensor_state, int robot_id);
00120 
00121 private:
00122 
00123   static bool JointDataToVector(const industrial::joint_data::JointData &joints,
00124                                 std::vector<double> &vec, int len);
00125 
00126 
00131   industrial::shared_types::shared_int valid_fields_from_message_;
00132 
00139   bool convert_message(JointFeedbackExMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00140 };  // class JointFeedbackExRelayHandler
00141 
00142 }  // namespace joint_feedback_ex_relay_handler
00143 }  // namespace industrial_robot_cliet
00144 
00145 #endif  // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H


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