Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
PheenoRobot Class Reference

#include <pheeno_robot.h>

Public Member Functions

void avoidObstaclesAngular (double &angular, double &random_turn_value, float angular_velocity=1.2, double range_to_avoid=20.0)
 
void avoidObstaclesLinear (double &linear, double &angular, float angular_velocity=1.2, float linear_velocity=0.08, double range_to_avoid=20.0)
 
bool checkFrontColor (int color)
 
bool irSensorTriggered (float sensor_limits)
 
 PheenoRobot (std::string pheeno_name)
 
void publish (geometry_msgs::Twist velocity)
 
double randomTurn (float angular=0.06)
 

Public Attributes

std::vector< double > accelerometer_vals_
 
std::vector< bool > color_state_facing_
 
std::vector< int > encoder_vals_
 
std::vector< double > gyroscope_vals_
 
std_msgs::Float32 ir_sensor_back_
 
std_msgs::Int16 ir_sensor_bottom_
 
std_msgs::Float32 ir_sensor_c_left_
 
std_msgs::Float32 ir_sensor_c_right_
 
std_msgs::Float32 ir_sensor_center_
 
std_msgs::Float32 ir_sensor_left_
 
std_msgs::Float32 ir_sensor_right_
 
std::vector< double > ir_sensor_vals_
 
std::vector< double > magnetometer_vals_
 
nav_msgs::Odometry odom_msg_
 
std::vector< double > odom_pose_orient_
 
std::vector< double > odom_pose_position_
 
std::vector< double > odom_twist_angular_
 
std::vector< double > odom_twist_linear_
 
std::string pheeno_namespace_id_
 

Private Member Functions

void accelerometerCallback (const geometry_msgs::Vector3::ConstPtr &msg)
 
void encoderLLCallback (const std_msgs::Int16::ConstPtr &msg)
 
void encoderLRCallback (const std_msgs::Int16::ConstPtr &msg)
 
void encoderRLCallback (const std_msgs::Int16::ConstPtr &msg)
 
void encoderRRCallback (const std_msgs::Int16::ConstPtr &msg)
 
void gyroscopeCallback (const geometry_msgs::Vector3::ConstPtr &msg)
 
void irSensorBackCallback (const std_msgs::Float32::ConstPtr &msg)
 
void irSensorBottomCallback (const std_msgs::Int16::ConstPtr &msg)
 
void irSensorCenterCallback (const std_msgs::Float32::ConstPtr &msg)
 
void irSensorCLeftCallback (const std_msgs::Float32::ConstPtr &msg)
 
void irSensorCRightCallback (const std_msgs::Float32::ConstPtr &msg)
 
void irSensorLeftCallback (const std_msgs::Float32::ConstPtr &msg)
 
void irSensorRightCallback (const std_msgs::Float32::ConstPtr &msg)
 
void magnetometerCallback (const geometry_msgs::Vector3::ConstPtr &msg)
 
void odomCallback (const nav_msgs::Odometry::ConstPtr &msg)
 
void piCamCallback ()
 

Private Attributes

ros::NodeHandle nh_
 
ros::Publisher pub_cmd_vel_
 
ros::Subscriber sub_accelerometer_
 
ros::Subscriber sub_encoder_LL_
 
ros::Subscriber sub_encoder_LR_
 
ros::Subscriber sub_encoder_RL_
 
ros::Subscriber sub_encoder_RR_
 
ros::Subscriber sub_gyroscope_
 
ros::Subscriber sub_ir_back_
 
ros::Subscriber sub_ir_bottom_
 
ros::Subscriber sub_ir_center_
 
ros::Subscriber sub_ir_cl_
 
ros::Subscriber sub_ir_cr_
 
ros::Subscriber sub_ir_left_
 
ros::Subscriber sub_ir_right_
 
ros::Subscriber sub_magnetometer_
 
ros::Subscriber sub_odom_
 
ros::Subscriber sub_pheeno_cam_
 

Detailed Description

Definition at line 35 of file pheeno_robot.h.

Constructor & Destructor Documentation

PheenoRobot::PheenoRobot ( std::string  pheeno_name)

Definition at line 20 of file pheeno_robot.cpp.

Member Function Documentation

void PheenoRobot::accelerometerCallback ( const geometry_msgs::Vector3::ConstPtr &  msg)
private

Definition at line 276 of file pheeno_robot.cpp.

void PheenoRobot::avoidObstaclesAngular ( double &  angular,
double &  random_turn_value,
float  angular_velocity = 1.2,
double  range_to_avoid = 20.0 
)

Definition at line 374 of file pheeno_robot.cpp.

void PheenoRobot::avoidObstaclesLinear ( double &  linear,
double &  angular,
float  angular_velocity = 1.2,
float  linear_velocity = 0.08,
double  range_to_avoid = 20.0 
)

Definition at line 311 of file pheeno_robot.cpp.

bool PheenoRobot::checkFrontColor ( int  color)
void PheenoRobot::encoderLLCallback ( const std_msgs::Int16::ConstPtr &  msg)
private

Definition at line 224 of file pheeno_robot.cpp.

void PheenoRobot::encoderLRCallback ( const std_msgs::Int16::ConstPtr &  msg)
private

Definition at line 232 of file pheeno_robot.cpp.

void PheenoRobot::encoderRLCallback ( const std_msgs::Int16::ConstPtr &  msg)
private

Definition at line 240 of file pheeno_robot.cpp.

void PheenoRobot::encoderRRCallback ( const std_msgs::Int16::ConstPtr &  msg)
private

Definition at line 248 of file pheeno_robot.cpp.

void PheenoRobot::gyroscopeCallback ( const geometry_msgs::Vector3::ConstPtr &  msg)
private

Definition at line 266 of file pheeno_robot.cpp.

void PheenoRobot::irSensorBackCallback ( const std_msgs::Float32::ConstPtr &  msg)
private

Definition at line 115 of file pheeno_robot.cpp.

void PheenoRobot::irSensorBottomCallback ( const std_msgs::Int16::ConstPtr &  msg)
private

Definition at line 181 of file pheeno_robot.cpp.

void PheenoRobot::irSensorCenterCallback ( const std_msgs::Float32::ConstPtr &  msg)
private

Definition at line 107 of file pheeno_robot.cpp.

void PheenoRobot::irSensorCLeftCallback ( const std_msgs::Float32::ConstPtr &  msg)
private

Definition at line 147 of file pheeno_robot.cpp.

void PheenoRobot::irSensorCRightCallback ( const std_msgs::Float32::ConstPtr &  msg)
private

Definition at line 139 of file pheeno_robot.cpp.

void PheenoRobot::irSensorLeftCallback ( const std_msgs::Float32::ConstPtr &  msg)
private

Definition at line 131 of file pheeno_robot.cpp.

void PheenoRobot::irSensorRightCallback ( const std_msgs::Float32::ConstPtr &  msg)
private

Definition at line 123 of file pheeno_robot.cpp.

bool PheenoRobot::irSensorTriggered ( float  sensor_limits)

Definition at line 156 of file pheeno_robot.cpp.

void PheenoRobot::magnetometerCallback ( const geometry_msgs::Vector3::ConstPtr &  msg)
private

Definition at line 256 of file pheeno_robot.cpp.

void PheenoRobot::odomCallback ( const nav_msgs::Odometry::ConstPtr &  msg)
private

Definition at line 201 of file pheeno_robot.cpp.

void PheenoRobot::piCamCallback ( )
private

Definition at line 290 of file pheeno_robot.cpp.

void PheenoRobot::publish ( geometry_msgs::Twist  velocity)

Definition at line 99 of file pheeno_robot.cpp.

double PheenoRobot::randomTurn ( float  angular = 0.06)

Definition at line 298 of file pheeno_robot.cpp.

Member Data Documentation

std::vector<double> PheenoRobot::accelerometer_vals_

Definition at line 57 of file pheeno_robot.h.

std::vector<bool> PheenoRobot::color_state_facing_

Definition at line 67 of file pheeno_robot.h.

std::vector<int> PheenoRobot::encoder_vals_

Definition at line 54 of file pheeno_robot.h.

std::vector<double> PheenoRobot::gyroscope_vals_

Definition at line 56 of file pheeno_robot.h.

std_msgs::Float32 PheenoRobot::ir_sensor_back_

Definition at line 47 of file pheeno_robot.h.

std_msgs::Int16 PheenoRobot::ir_sensor_bottom_

Definition at line 52 of file pheeno_robot.h.

std_msgs::Float32 PheenoRobot::ir_sensor_c_left_

Definition at line 51 of file pheeno_robot.h.

std_msgs::Float32 PheenoRobot::ir_sensor_c_right_

Definition at line 50 of file pheeno_robot.h.

std_msgs::Float32 PheenoRobot::ir_sensor_center_

Definition at line 46 of file pheeno_robot.h.

std_msgs::Float32 PheenoRobot::ir_sensor_left_

Definition at line 49 of file pheeno_robot.h.

std_msgs::Float32 PheenoRobot::ir_sensor_right_

Definition at line 48 of file pheeno_robot.h.

std::vector<double> PheenoRobot::ir_sensor_vals_

Definition at line 53 of file pheeno_robot.h.

std::vector<double> PheenoRobot::magnetometer_vals_

Definition at line 55 of file pheeno_robot.h.

ros::NodeHandle PheenoRobot::nh_
private

Definition at line 88 of file pheeno_robot.h.

nav_msgs::Odometry PheenoRobot::odom_msg_

Definition at line 60 of file pheeno_robot.h.

std::vector<double> PheenoRobot::odom_pose_orient_

Definition at line 62 of file pheeno_robot.h.

std::vector<double> PheenoRobot::odom_pose_position_

Definition at line 61 of file pheeno_robot.h.

std::vector<double> PheenoRobot::odom_twist_angular_

Definition at line 64 of file pheeno_robot.h.

std::vector<double> PheenoRobot::odom_twist_linear_

Definition at line 63 of file pheeno_robot.h.

std::string PheenoRobot::pheeno_namespace_id_

Definition at line 43 of file pheeno_robot.h.

ros::Publisher PheenoRobot::pub_cmd_vel_
private

Definition at line 109 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_accelerometer_
private

Definition at line 106 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_encoder_LL_
private

Definition at line 100 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_encoder_LR_
private

Definition at line 101 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_encoder_RL_
private

Definition at line 102 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_encoder_RR_
private

Definition at line 103 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_gyroscope_
private

Definition at line 105 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_ir_back_
private

Definition at line 96 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_ir_bottom_
private

Definition at line 97 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_ir_center_
private

Definition at line 91 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_ir_cl_
private

Definition at line 95 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_ir_cr_
private

Definition at line 94 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_ir_left_
private

Definition at line 93 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_ir_right_
private

Definition at line 92 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_magnetometer_
private

Definition at line 104 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_odom_
private

Definition at line 99 of file pheeno_robot.h.

ros::Subscriber PheenoRobot::sub_pheeno_cam_
private

Definition at line 98 of file pheeno_robot.h.


The documentation for this class was generated from the following files:


pheeno_ros
Author(s): Zahi Kakish, Sean Wilson
autogenerated on Mon Jun 10 2019 14:10:48