#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_values | 
| std::vector< bool > | color_state_facing | 
| std::vector< int > | encoder_values | 
| std::vector< double > | gyroscope_values | 
| 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_values | 
| std::vector< double > | magnetometer_values | 
| 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_ | 
Definition at line 14 of file pheeno_robot.h.
| PheenoRobot::PheenoRobot | ( | std::string | pheeno_name | ) | 
Definition at line 20 of file pheeno_robot.cpp.
| void PheenoRobot::accelerometerCallback | ( | const geometry_msgs::Vector3::ConstPtr & | msg | ) |  [private] | 
Definition at line 282 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 380 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 317 of file pheeno_robot.cpp.
| bool PheenoRobot::checkFrontColor | ( | int | color | ) | 
| void PheenoRobot::encoderLLCallback | ( | const std_msgs::Int16::ConstPtr & | msg | ) |  [private] | 
Definition at line 230 of file pheeno_robot.cpp.
| void PheenoRobot::encoderLRCallback | ( | const std_msgs::Int16::ConstPtr & | msg | ) |  [private] | 
Definition at line 238 of file pheeno_robot.cpp.
| void PheenoRobot::encoderRLCallback | ( | const std_msgs::Int16::ConstPtr & | msg | ) |  [private] | 
Definition at line 246 of file pheeno_robot.cpp.
| void PheenoRobot::encoderRRCallback | ( | const std_msgs::Int16::ConstPtr & | msg | ) |  [private] | 
Definition at line 254 of file pheeno_robot.cpp.
| void PheenoRobot::gyroscopeCallback | ( | const geometry_msgs::Vector3::ConstPtr & | msg | ) |  [private] | 
Definition at line 272 of file pheeno_robot.cpp.
| void PheenoRobot::irSensorBackCallback | ( | const std_msgs::Float32::ConstPtr & | msg | ) |  [private] | 
Definition at line 116 of file pheeno_robot.cpp.
| void PheenoRobot::irSensorBottomCallback | ( | const std_msgs::Int16::ConstPtr & | msg | ) |  [private] | 
Definition at line 187 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 152 of file pheeno_robot.cpp.
| void PheenoRobot::irSensorCRightCallback | ( | const std_msgs::Float32::ConstPtr & | msg | ) |  [private] | 
Definition at line 143 of file pheeno_robot.cpp.
| void PheenoRobot::irSensorLeftCallback | ( | const std_msgs::Float32::ConstPtr & | msg | ) |  [private] | 
Definition at line 134 of file pheeno_robot.cpp.
| void PheenoRobot::irSensorRightCallback | ( | const std_msgs::Float32::ConstPtr & | msg | ) |  [private] | 
Definition at line 125 of file pheeno_robot.cpp.
| bool PheenoRobot::irSensorTriggered | ( | float | sensor_limits | ) | 
Definition at line 162 of file pheeno_robot.cpp.
| void PheenoRobot::magnetometerCallback | ( | const geometry_msgs::Vector3::ConstPtr & | msg | ) |  [private] | 
Definition at line 262 of file pheeno_robot.cpp.
| void PheenoRobot::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |  [private] | 
Definition at line 207 of file pheeno_robot.cpp.
| void PheenoRobot::piCamCallback | ( | ) |  [private] | 
Definition at line 296 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 304 of file pheeno_robot.cpp.
| std::vector<double> PheenoRobot::accelerometer_values | 
Definition at line 35 of file pheeno_robot.h.
| std::vector<bool> PheenoRobot::color_state_facing | 
Definition at line 45 of file pheeno_robot.h.
| std::vector<int> PheenoRobot::encoder_values | 
Definition at line 32 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::gyroscope_values | 
Definition at line 34 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_back | 
Definition at line 25 of file pheeno_robot.h.
| std_msgs::Int16 PheenoRobot::ir_sensor_bottom | 
Definition at line 30 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_c_left | 
Definition at line 29 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_c_right | 
Definition at line 28 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_center | 
Definition at line 24 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_left | 
Definition at line 27 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_right | 
Definition at line 26 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::ir_sensor_values | 
Definition at line 31 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::magnetometer_values | 
Definition at line 33 of file pheeno_robot.h.
| ros::NodeHandle PheenoRobot::nh_  [private] | 
Definition at line 66 of file pheeno_robot.h.
| nav_msgs::Odometry PheenoRobot::odom_msg | 
Definition at line 38 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::odom_pose_orient | 
Definition at line 40 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::odom_pose_position | 
Definition at line 39 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::odom_twist_angular | 
Definition at line 42 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::odom_twist_linear | 
Definition at line 41 of file pheeno_robot.h.
| std::string PheenoRobot::pheeno_namespace_id | 
Definition at line 21 of file pheeno_robot.h.
| ros::Publisher PheenoRobot::pub_cmd_vel_  [private] | 
Definition at line 87 of file pheeno_robot.h.
Definition at line 84 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_encoder_LL_  [private] | 
Definition at line 78 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_encoder_LR_  [private] | 
Definition at line 79 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_encoder_RL_  [private] | 
Definition at line 80 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_encoder_RR_  [private] | 
Definition at line 81 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_gyroscope_  [private] | 
Definition at line 83 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_ir_back_  [private] | 
Definition at line 74 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_ir_bottom_  [private] | 
Definition at line 75 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_ir_center_  [private] | 
Definition at line 69 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_ir_cl_  [private] | 
Definition at line 73 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_ir_cr_  [private] | 
Definition at line 72 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_ir_left_  [private] | 
Definition at line 71 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_ir_right_  [private] | 
Definition at line 70 of file pheeno_robot.h.
Definition at line 82 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_odom_  [private] | 
Definition at line 77 of file pheeno_robot.h.
| ros::Subscriber PheenoRobot::sub_pheeno_cam_  [private] | 
Definition at line 76 of file pheeno_robot.h.