pheeno_robot.h
Go to the documentation of this file.
1 #ifndef PHEENO_ROS_SIM_PHEENO_ROBOT_H
2 #define PHEENO_ROS_SIM_PHEENO_ROBOT_H
3 
4 #include "ros/ros.h"
5 #include "std_msgs/Float32.h"
6 #include "std_msgs/Int16.h"
7 #include "geometry_msgs/Twist.h"
8 #include "geometry_msgs/Vector3.h"
9 #include "nav_msgs/Odometry.h"
10 #include <vector>
11 #include <complex>
12 #include <cstdlib>
13 
15 {
16 
17 public:
18  // Constructor
19  PheenoRobot(std::string pheeno_name);
20 
21  // Pheeno name
22  std::string pheeno_namespace_id_;
23 
24  // Sensor Messages
25  std_msgs::Float32 ir_sensor_center_;
26  std_msgs::Float32 ir_sensor_back_;
27  std_msgs::Float32 ir_sensor_right_;
28  std_msgs::Float32 ir_sensor_left_;
29  std_msgs::Float32 ir_sensor_c_right_;
30  std_msgs::Float32 ir_sensor_c_left_;
31  std_msgs::Int16 ir_sensor_bottom_;
32  std::vector<double> ir_sensor_values_;
33  std::vector<int> encoder_values_;
34  std::vector<double> magnetometer_values_;
35  std::vector<double> gyroscope_values_;
36  std::vector<double> accelerometer_values_;
37 
38  // Odometry Messages
39  nav_msgs::Odometry odom_msg_;
40  std::vector<double> odom_pose_position_;
41  std::vector<double> odom_pose_orient_;
42  std::vector<double> odom_twist_linear_;
43  std::vector<double> odom_twist_angular_;
44 
45  // Camera Messages
46  std::vector<bool> color_state_facing_;
47 
48  // Public Sensor Methods
49  bool irSensorTriggered(float sensor_limits);
50 
51  // Public Movement Methods
52  double randomTurn(float angular = 0.06);
53  void avoidObstaclesLinear(double &linear, double &angular,
54  float angular_velocity = 1.2, float linear_velocity = 0.08,
55  double range_to_avoid = 20.0);
56  void avoidObstaclesAngular(double &angular, double &random_turn_value,
57  float angular_velocity = 1.2, double range_to_avoid = 20.0);
58 
59  // Public Publishers
60  void publish(geometry_msgs::Twist velocity);
61 
62  // Public camera methods
63  bool checkFrontColor(int color);
64 
65 private:
66  // ROS Node handle
68 
69  // Private Subscribers
86 
87  // Private Publishers
89 
90  // IR Callback Methods
91  void irSensorCenterCallback(const std_msgs::Float32::ConstPtr& msg);
92  void irSensorBackCallback(const std_msgs::Float32::ConstPtr& msg);
93  void irSensorRightCallback(const std_msgs::Float32::ConstPtr& msg);
94  void irSensorLeftCallback(const std_msgs::Float32::ConstPtr& msg);
95  void irSensorCRightCallback(const std_msgs::Float32::ConstPtr& msg);
96  void irSensorCLeftCallback(const std_msgs::Float32::ConstPtr& msg);
97  void irSensorBottomCallback(const std_msgs::Int16::ConstPtr& msg);
98 
99  // Odom Callback Methods
100  void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
101 
102  // Encoder Callback Methods
103  void encoderLLCallback(const std_msgs::Int16::ConstPtr& msg);
104  void encoderLRCallback(const std_msgs::Int16::ConstPtr& msg);
105  void encoderRLCallback(const std_msgs::Int16::ConstPtr& msg);
106  void encoderRRCallback(const std_msgs::Int16::ConstPtr& msg);
107 
108  // Other Sensor Callback Methods
109  void magnetometerCallback(const geometry_msgs::Vector3::ConstPtr& msg);
110  void gyroscopeCallback(const geometry_msgs::Vector3::ConstPtr& msg);
111  void accelerometerCallback(const geometry_msgs::Vector3::ConstPtr& msg);
112 
113  // Camera Callback Modules
114  void piCamCallback();
115 };
116 
117 #endif //GUARD_PHEENO_ROBOT_H
bool irSensorTriggered(float sensor_limits)
void irSensorCLeftCallback(const std_msgs::Float32::ConstPtr &msg)
ros::NodeHandle nh_
Definition: pheeno_robot.h:67
void accelerometerCallback(const geometry_msgs::Vector3::ConstPtr &msg)
bool checkFrontColor(int color)
void publish(geometry_msgs::Twist velocity)
void irSensorBottomCallback(const std_msgs::Int16::ConstPtr &msg)
void gyroscopeCallback(const geometry_msgs::Vector3::ConstPtr &msg)
ros::Subscriber sub_pheeno_cam_
Definition: pheeno_robot.h:77
std::vector< double > gyroscope_values_
Definition: pheeno_robot.h:35
PheenoRobot(std::string pheeno_name)
ros::Subscriber sub_ir_cr_
Definition: pheeno_robot.h:73
std::vector< double > magnetometer_values_
Definition: pheeno_robot.h:34
ros::Subscriber sub_odom_
Definition: pheeno_robot.h:78
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
void encoderRLCallback(const std_msgs::Int16::ConstPtr &msg)
void irSensorCenterCallback(const std_msgs::Float32::ConstPtr &msg)
std_msgs::Float32 ir_sensor_back_
Definition: pheeno_robot.h:26
std_msgs::Float32 ir_sensor_center_
Definition: pheeno_robot.h:25
ros::Subscriber sub_gyroscope_
Definition: pheeno_robot.h:84
std::vector< double > odom_pose_position_
Definition: pheeno_robot.h:40
ros::Subscriber sub_encoder_RL_
Definition: pheeno_robot.h:81
ros::Subscriber sub_magnetometer_
Definition: pheeno_robot.h:83
nav_msgs::Odometry odom_msg_
Definition: pheeno_robot.h:39
void irSensorBackCallback(const std_msgs::Float32::ConstPtr &msg)
ros::Subscriber sub_ir_left_
Definition: pheeno_robot.h:72
ros::Subscriber sub_encoder_LR_
Definition: pheeno_robot.h:80
std_msgs::Int16 ir_sensor_bottom_
Definition: pheeno_robot.h:31
std_msgs::Float32 ir_sensor_c_right_
Definition: pheeno_robot.h:29
std::vector< double > odom_twist_angular_
Definition: pheeno_robot.h:43
void magnetometerCallback(const geometry_msgs::Vector3::ConstPtr &msg)
ros::Subscriber sub_ir_bottom_
Definition: pheeno_robot.h:76
std::vector< double > odom_pose_orient_
Definition: pheeno_robot.h:41
std_msgs::Float32 ir_sensor_c_left_
Definition: pheeno_robot.h:30
std_msgs::Float32 ir_sensor_right_
Definition: pheeno_robot.h:27
ros::Subscriber sub_encoder_RR_
Definition: pheeno_robot.h:82
ros::Subscriber sub_ir_center_
Definition: pheeno_robot.h:70
ros::Subscriber sub_ir_right_
Definition: pheeno_robot.h:71
std::vector< double > odom_twist_linear_
Definition: pheeno_robot.h:42
ros::Subscriber sub_accelerometer_
Definition: pheeno_robot.h:85
void piCamCallback()
void encoderLRCallback(const std_msgs::Int16::ConstPtr &msg)
ros::Subscriber sub_encoder_LL_
Definition: pheeno_robot.h:79
ros::Publisher pub_cmd_vel_
Definition: pheeno_robot.h:88
void avoidObstaclesAngular(double &angular, double &random_turn_value, float angular_velocity=1.2, double range_to_avoid=20.0)
ros::Subscriber sub_ir_back_
Definition: pheeno_robot.h:75
ros::Subscriber sub_ir_cl_
Definition: pheeno_robot.h:74
void encoderLLCallback(const std_msgs::Int16::ConstPtr &msg)
void encoderRRCallback(const std_msgs::Int16::ConstPtr &msg)
void irSensorLeftCallback(const std_msgs::Float32::ConstPtr &msg)
std::vector< double > ir_sensor_values_
Definition: pheeno_robot.h:32
double randomTurn(float angular=0.06)
void irSensorCRightCallback(const std_msgs::Float32::ConstPtr &msg)
std_msgs::Float32 ir_sensor_left_
Definition: pheeno_robot.h:28
std::vector< int > encoder_values_
Definition: pheeno_robot.h:33
std::vector< double > accelerometer_values_
Definition: pheeno_robot.h:36
std::string pheeno_namespace_id_
Definition: pheeno_robot.h:22
void irSensorRightCallback(const std_msgs::Float32::ConstPtr &msg)
std::vector< bool > color_state_facing_
Definition: pheeno_robot.h:46
void avoidObstaclesLinear(double &linear, double &angular, float angular_velocity=1.2, float linear_velocity=0.08, double range_to_avoid=20.0)


pheeno_ros_sim
Author(s): Zahi Kakish
autogenerated on Mon Jun 10 2019 14:25:55