00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef SKINSAFEBASE_H_
00033 #define SKINSAFEBASE_H_
00034
00035
00036 #include <ros/ros.h>
00037 #include <std_msgs/Bool.h>
00038 #include <geometry_msgs/Twist.h>
00039 #include <safe_base_controller/TwistLimits.h>
00040
00041
00042 #include "skin_driver/skin_meas.h"
00043
00044
00046
00049 class SkinSafeBase {
00050 public:
00051 SkinSafeBase();
00052 virtual ~SkinSafeBase();
00053
00054 private:
00055
00056 void skinNewMeasCallback(const boost::shared_ptr<skin_driver::skin_meas const>& msg);
00057 void newBaseCommandCallback(const boost::shared_ptr<geometry_msgs::Twist const>& msg);
00058
00059 bool checkPatchesBlocked(std::vector<int> & patches);
00060
00061 void loadParameterDouble(ros::NodeHandle & nh_, std::string param, double & data);
00062 void loadParameterInt(ros::NodeHandle & nh_, std::string param, int & data);
00063 void loadParameterIntArray(ros::NodeHandle & nh_, std::string param, std::vector<int> & vec);
00064
00065
00066 ros::NodeHandle nh_;
00067 ros::NodeHandle nh_private_;
00068 ros::Subscriber sub_skin_data_;
00069 ros::Publisher pub_cmd_vel_limits_;
00070
00071 int num_sensors_;
00072 int sensor_threshold_;
00073 double max_vel_;
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084 std::vector<int> patches_bl_, patches_br_, patches_fl_, patches_fr_, patches_rb_, patches_rf_, patches_lb_, patches_lf_;
00085
00086
00087 bool blocked_bl_, blocked_br_, blocked_fl_, blocked_fr_, blocked_rb_, blocked_rf_, blocked_lb_, blocked_lf_;
00088
00089 struct sensor_data_struct {
00090 uint8_t id;
00091 uint8_t stat;
00092 uint8_t x;
00093 uint8_t ini;
00094 uint8_t limit;
00095 uint8_t u1;
00096 uint8_t u2;
00097 uint8_t u3;
00098 uint8_t dyn;
00099 };
00100
00101
00102 std::vector<sensor_data_struct> sensor_data_;
00103 };
00104
00105 #endif