R2RosArbiter.hpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include "r2_msgs/LabeledControllerJointSettings.h"
00003 #include "r2_msgs/LabeledControllerPoseSettings.h"
00004 #include "r2_msgs/LabeledJointState.h"
00005 #include "r2_msgs/LabeledGains.h"
00006 #include "r2_msgs/LabeledJointTrajectory.h"
00007 #include "r2_msgs/LabeledPoseTrajectory.h"
00008 #include "r2_msgs/LabeledGripperPositionCommand.h"
00009 #include "r2_msgs/Modes.h"
00010 
00011 #include "r2_msgs/ControllerJointSettings.h"
00012 #include "r2_msgs/ControllerPoseSettings.h"
00013 #include "sensor_msgs/JointState.h"
00014 #include "r2_msgs/Gains.h"
00015 #include "r2_msgs/JointTrajectoryReplan.h"
00016 #include "r2_msgs/PoseTrajectoryReplan.h"
00017 #include "r2_msgs/GripperPositionCommand.h"
00018 
00019 #include "actionlib_msgs/GoalStatusArray.h"
00020 
00024 class R2RosArbiter
00025 {
00026 public:
00027     R2RosArbiter(ros::NodeHandle nh);
00028     virtual ~R2RosArbiter() {}
00029 
00030     void modeCallback(const r2_msgs::Modes& msg);
00031 
00032     void labeledJointSettingsCallback(const r2_msgs::LabeledControllerJointSettings& msg);
00033     void labeledPoseSettingsCallback(const r2_msgs::LabeledControllerPoseSettings& msg);
00034     void labeledJointStateCallback(const r2_msgs::LabeledJointState& msg);
00035     void labeledGainsCallback(const r2_msgs::LabeledGains& msg);
00036     void labeledJointRefCallback(const r2_msgs::LabeledJointTrajectory& msg);
00037     void labeledJointTrajCallback(const r2_msgs::LabeledJointTrajectory& msg);
00038     void labeledPoseTrajectoryCallback(const r2_msgs::LabeledPoseTrajectory& msg);
00039     void labeledGripperCommandCallback(const r2_msgs::LabeledGripperPositionCommand& msg);
00040 
00041 private:
00042     void writeSuccessStatus(std::string id);
00043 
00044     ros::NodeHandle nh;
00045 
00046     ros::Subscriber modeIn;
00047     ros::Subscriber labeledJointSettingsIn;
00048     ros::Subscriber labeledPoseSettingsIn;
00049     ros::Subscriber labeledJointStateIn;
00050     ros::Subscriber labeledGainsIn;
00051     ros::Subscriber labeledJointRefIn;
00052     ros::Subscriber labeledJointTrajIn;
00053     ros::Subscriber labeledPoseTrajIn;
00054     ros::Subscriber labeledGripperCommandIn;
00055 
00056     ros::Publisher jointSettingsOut;
00057     ros::Publisher poseSettingsOut;
00058     ros::Publisher jointStateOut;
00059     ros::Publisher gainsOut;
00060     ros::Publisher jointRefsOut;
00061     ros::Publisher jointTrajOut;
00062     ros::Publisher poseTrajOut;
00063     ros::Publisher gripperCmdOut;
00064 
00065     ros::Publisher goalStatusOut;
00066 };


robodyn_ros
Author(s):
autogenerated on Thu Jun 6 2019 18:14:39