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


r2_controllers_ros
Author(s): Allison Thackston
autogenerated on Mon Oct 6 2014 02:46:50