SkinSafeBase class. More...
#include <skin_safe_base.h>
Classes | |
struct | sensor_data_struct |
Public Member Functions | |
SkinSafeBase () | |
Constructor initializes SkinSafeBase. | |
virtual | ~SkinSafeBase () |
Destructor of SkinSafeBase. | |
Private Member Functions | |
bool | checkPatchesBlocked (std::vector< int > &patches) |
updateBlockedPatches | |
void | loadParameterDouble (ros::NodeHandle &nh_, std::string param, double &data) |
Loads double parameter from ROS parameter server. | |
void | loadParameterInt (ros::NodeHandle &nh_, std::string param, int &data) |
Loads integer parameter from ROS parameter server. | |
void | loadParameterIntArray (ros::NodeHandle &nh_, std::string param, std::vector< int > &vec) |
Loads integer array parameter from ROS parameter server. | |
void | newBaseCommandCallback (const boost::shared_ptr< geometry_msgs::Twist const > &msg) |
void | skinNewMeasCallback (const boost::shared_ptr< skin_driver::skin_meas const > &msg) |
Callback function which is called when new skin message arrives. | |
Private Attributes | |
bool | blocked_bl_ |
bool | blocked_br_ |
bool | blocked_fl_ |
bool | blocked_fr_ |
bool | blocked_lb_ |
bool | blocked_lf_ |
bool | blocked_rb_ |
bool | blocked_rf_ |
double | max_vel_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_private_ |
int | num_sensors_ |
std::vector< int > | patches_bl_ |
std::vector< int > | patches_br_ |
std::vector< int > | patches_fl_ |
std::vector< int > | patches_fr_ |
std::vector< int > | patches_lb_ |
std::vector< int > | patches_lf_ |
std::vector< int > | patches_rb_ |
std::vector< int > | patches_rf_ |
ros::Publisher | pub_cmd_vel_limits_ |
std::vector< sensor_data_struct > | sensor_data_ |
int | sensor_threshold_ |
ros::Subscriber | sub_skin_data_ |
SkinSafeBase class.
Definition at line 49 of file skin_safe_base.h.
SkinSafeBase::SkinSafeBase | ( | ) |
Constructor initializes SkinSafeBase.
Initialize buffers, subscribe to skin_data message
Definition at line 39 of file skin_safe_base.cpp.
SkinSafeBase::~SkinSafeBase | ( | ) | [virtual] |
Destructor of SkinSafeBase.
Definition at line 65 of file skin_safe_base.cpp.
bool SkinSafeBase::checkPatchesBlocked | ( | std::vector< int > & | patches | ) | [private] |
updateBlockedPatches
Returns false if no skin patch of group (ids of skin patches of group are stored in vector patches) is activated. Returns true if one or more patches are activated.
Definition at line 162 of file skin_safe_base.cpp.
void SkinSafeBase::loadParameterDouble | ( | ros::NodeHandle & | nh_, | |
std::string | param, | |||
double & | data | |||
) | [private] |
Loads double parameter from ROS parameter server.
Loads parameter, if parameter not present notifies user and exits.
nh_ | Node Handle to use | |
param | Name of parameter to load | |
data | Contains loaded parameter from server |
Definition at line 210 of file skin_safe_base.cpp.
void SkinSafeBase::loadParameterInt | ( | ros::NodeHandle & | nh_, | |
std::string | param, | |||
int & | data | |||
) | [private] |
Loads integer parameter from ROS parameter server.
Loads parameter, if parameter not present notifies user and exits.
nh_ | Node Handle to use | |
param | Name of parameter to load | |
data | Contains loaded parameter from server |
Definition at line 231 of file skin_safe_base.cpp.
void SkinSafeBase::loadParameterIntArray | ( | ros::NodeHandle & | nh_, | |
std::string | param, | |||
std::vector< int > & | vec | |||
) | [private] |
Loads integer array parameter from ROS parameter server.
Loads parameter array, if parameter not present notifies user and exits. Parameter array is returned as std::vector<int>.
nh_ | Node Handle to use | |
param | Name of parameter to load | |
vec | Contains loaded parameter from server |
Definition at line 253 of file skin_safe_base.cpp.
void SkinSafeBase::newBaseCommandCallback | ( | const boost::shared_ptr< geometry_msgs::Twist const > & | msg | ) | [private] |
void SkinSafeBase::skinNewMeasCallback | ( | const boost::shared_ptr< skin_driver::skin_meas const > & | msg | ) | [private] |
Callback function which is called when new skin message arrives.
Converts skin message and sends abort message.
msg | skin_data message. |
Definition at line 74 of file skin_safe_base.cpp.
bool SkinSafeBase::blocked_bl_ [private] |
Definition at line 81 of file skin_safe_base.h.
bool SkinSafeBase::blocked_br_ [private] |
Definition at line 81 of file skin_safe_base.h.
bool SkinSafeBase::blocked_fl_ [private] |
Definition at line 81 of file skin_safe_base.h.
bool SkinSafeBase::blocked_fr_ [private] |
Definition at line 81 of file skin_safe_base.h.
bool SkinSafeBase::blocked_lb_ [private] |
Definition at line 81 of file skin_safe_base.h.
bool SkinSafeBase::blocked_lf_ [private] |
Definition at line 81 of file skin_safe_base.h.
bool SkinSafeBase::blocked_rb_ [private] |
Definition at line 81 of file skin_safe_base.h.
bool SkinSafeBase::blocked_rf_ [private] |
Definition at line 81 of file skin_safe_base.h.
double SkinSafeBase::max_vel_ [private] |
Definition at line 67 of file skin_safe_base.h.
ros::NodeHandle SkinSafeBase::nh_ [private] |
Definition at line 60 of file skin_safe_base.h.
ros::NodeHandle SkinSafeBase::nh_private_ [private] |
Definition at line 61 of file skin_safe_base.h.
int SkinSafeBase::num_sensors_ [private] |
Definition at line 65 of file skin_safe_base.h.
std::vector<int> SkinSafeBase::patches_bl_ [private] |
Definition at line 78 of file skin_safe_base.h.
std::vector<int> SkinSafeBase::patches_br_ [private] |
Definition at line 78 of file skin_safe_base.h.
std::vector<int> SkinSafeBase::patches_fl_ [private] |
Definition at line 78 of file skin_safe_base.h.
std::vector<int> SkinSafeBase::patches_fr_ [private] |
Definition at line 78 of file skin_safe_base.h.
std::vector<int> SkinSafeBase::patches_lb_ [private] |
Definition at line 78 of file skin_safe_base.h.
std::vector<int> SkinSafeBase::patches_lf_ [private] |
Definition at line 78 of file skin_safe_base.h.
std::vector<int> SkinSafeBase::patches_rb_ [private] |
Definition at line 78 of file skin_safe_base.h.
std::vector<int> SkinSafeBase::patches_rf_ [private] |
Definition at line 78 of file skin_safe_base.h.
ros::Publisher SkinSafeBase::pub_cmd_vel_limits_ [private] |
Definition at line 63 of file skin_safe_base.h.
std::vector<sensor_data_struct> SkinSafeBase::sensor_data_ [private] |
Definition at line 96 of file skin_safe_base.h.
int SkinSafeBase::sensor_threshold_ [private] |
Definition at line 66 of file skin_safe_base.h.
ros::Subscriber SkinSafeBase::sub_skin_data_ [private] |
Definition at line 62 of file skin_safe_base.h.