#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 () |
Definition at line 14 of file pheeno_robot.h.
| PheenoRobot::PheenoRobot | ( | std::string | pheeno_name | ) |
Definition at line 20 of file pheeno_robot.cpp.
|
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 | ) |
|
private |
Definition at line 230 of file pheeno_robot.cpp.
|
private |
Definition at line 238 of file pheeno_robot.cpp.
|
private |
Definition at line 246 of file pheeno_robot.cpp.
|
private |
Definition at line 254 of file pheeno_robot.cpp.
|
private |
Definition at line 272 of file pheeno_robot.cpp.
|
private |
Definition at line 116 of file pheeno_robot.cpp.
|
private |
Definition at line 187 of file pheeno_robot.cpp.
|
private |
Definition at line 107 of file pheeno_robot.cpp.
|
private |
Definition at line 152 of file pheeno_robot.cpp.
|
private |
Definition at line 143 of file pheeno_robot.cpp.
|
private |
Definition at line 134 of file pheeno_robot.cpp.
|
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.
|
private |
Definition at line 262 of file pheeno_robot.cpp.
|
private |
Definition at line 207 of file pheeno_robot.cpp.
|
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 36 of file pheeno_robot.h.
| std::vector<bool> PheenoRobot::color_state_facing_ |
Definition at line 46 of file pheeno_robot.h.
| std::vector<int> PheenoRobot::encoder_values_ |
Definition at line 33 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::gyroscope_values_ |
Definition at line 35 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_back_ |
Definition at line 26 of file pheeno_robot.h.
| std_msgs::Int16 PheenoRobot::ir_sensor_bottom_ |
Definition at line 31 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_c_left_ |
Definition at line 30 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_c_right_ |
Definition at line 29 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_center_ |
Definition at line 25 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_left_ |
Definition at line 28 of file pheeno_robot.h.
| std_msgs::Float32 PheenoRobot::ir_sensor_right_ |
Definition at line 27 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::ir_sensor_values_ |
Definition at line 32 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::magnetometer_values_ |
Definition at line 34 of file pheeno_robot.h.
|
private |
Definition at line 67 of file pheeno_robot.h.
| nav_msgs::Odometry PheenoRobot::odom_msg_ |
Definition at line 39 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::odom_pose_orient_ |
Definition at line 41 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::odom_pose_position_ |
Definition at line 40 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::odom_twist_angular_ |
Definition at line 43 of file pheeno_robot.h.
| std::vector<double> PheenoRobot::odom_twist_linear_ |
Definition at line 42 of file pheeno_robot.h.
| std::string PheenoRobot::pheeno_namespace_id_ |
Definition at line 22 of file pheeno_robot.h.
|
private |
Definition at line 88 of file pheeno_robot.h.
|
private |
Definition at line 85 of file pheeno_robot.h.
|
private |
Definition at line 79 of file pheeno_robot.h.
|
private |
Definition at line 80 of file pheeno_robot.h.
|
private |
Definition at line 81 of file pheeno_robot.h.
|
private |
Definition at line 82 of file pheeno_robot.h.
|
private |
Definition at line 84 of file pheeno_robot.h.
|
private |
Definition at line 75 of file pheeno_robot.h.
|
private |
Definition at line 76 of file pheeno_robot.h.
|
private |
Definition at line 70 of file pheeno_robot.h.
|
private |
Definition at line 74 of file pheeno_robot.h.
|
private |
Definition at line 73 of file pheeno_robot.h.
|
private |
Definition at line 72 of file pheeno_robot.h.
|
private |
Definition at line 71 of file pheeno_robot.h.
|
private |
Definition at line 83 of file pheeno_robot.h.
|
private |
Definition at line 78 of file pheeno_robot.h.
|
private |
Definition at line 77 of file pheeno_robot.h.