pheeno_robot.h
Go to the documentation of this file.
00001 #ifndef GUARD_PHEENO_ROBOT_H
00002 #define GUARD_PHEENO_ROBOT_H
00003 
00004 #include "ros/ros.h"
00005 #include "std_msgs/Float32.h"
00006 #include "std_msgs/Int16.h"
00007 #include "geometry_msgs/Twist.h"
00008 #include "geometry_msgs/Vector3.h"
00009 #include "nav_msgs/Odometry.h"
00010 #include <vector>
00011 #include <complex>
00012 #include <cstdlib>
00013 
00014 class PheenoRobot {
00015 
00016 public:
00017   // Constructor
00018   PheenoRobot(std::string pheeno_name);
00019 
00020   // Pheeno name
00021   std::string pheeno_namespace_id;
00022 
00023   // Sensor Messages
00024   std_msgs::Float32 ir_sensor_center;
00025   std_msgs::Float32 ir_sensor_back;
00026   std_msgs::Float32 ir_sensor_right;
00027   std_msgs::Float32 ir_sensor_left;
00028   std_msgs::Float32 ir_sensor_c_right;
00029   std_msgs::Float32 ir_sensor_c_left;
00030   std_msgs::Int16 ir_sensor_bottom;
00031   std::vector<double> ir_sensor_values;
00032   std::vector<int> encoder_values;
00033   std::vector<double> magnetometer_values;
00034   std::vector<double> gyroscope_values;
00035   std::vector<double> accelerometer_values;
00036 
00037   // Odometry Messages
00038   nav_msgs::Odometry odom_msg;
00039   std::vector<double> odom_pose_position;
00040   std::vector<double> odom_pose_orient;
00041   std::vector<double> odom_twist_linear;
00042   std::vector<double> odom_twist_angular;
00043 
00044   // Camera Messages
00045   std::vector<bool> color_state_facing;
00046 
00047   // Public Sensor Methods
00048   bool irSensorTriggered(float sensor_limits);
00049 
00050   // Public Movement Methods
00051   double randomTurn(float angular = 0.06);
00052   void avoidObstaclesLinear(double &linear, double &angular,
00053                             float angular_velocity = 1.2, float linear_velocity = 0.08,
00054                             double range_to_avoid = 20.0);
00055   void avoidObstaclesAngular(double &angular, double &random_turn_value,
00056                              float angular_velocity = 1.2, double range_to_avoid = 20.0);
00057 
00058   // Public Publishers
00059   void publish(geometry_msgs::Twist velocity);
00060 
00061   // Public camera methods
00062   bool checkFrontColor(int color);
00063 
00064 private:
00065   // ROS Node handle
00066   ros::NodeHandle nh_;
00067 
00068   // Private Subscribers
00069   ros::Subscriber sub_ir_center_;
00070   ros::Subscriber sub_ir_right_;
00071   ros::Subscriber sub_ir_left_;
00072   ros::Subscriber sub_ir_cr_;
00073   ros::Subscriber sub_ir_cl_;
00074   ros::Subscriber sub_ir_back_;
00075   ros::Subscriber sub_ir_bottom_;
00076   ros::Subscriber sub_pheeno_cam_;
00077   ros::Subscriber sub_odom_;
00078   ros::Subscriber sub_encoder_LL_;
00079   ros::Subscriber sub_encoder_LR_;
00080   ros::Subscriber sub_encoder_RL_;
00081   ros::Subscriber sub_encoder_RR_;
00082   ros::Subscriber sub_magnetometer_;
00083   ros::Subscriber sub_gyroscope_;
00084   ros::Subscriber sub_accelerometer_;
00085 
00086   // Private Publishers
00087   ros::Publisher pub_cmd_vel_;
00088 
00089   // IR Callback Methods
00090   void irSensorCenterCallback(const std_msgs::Float32::ConstPtr& msg);
00091   void irSensorBackCallback(const std_msgs::Float32::ConstPtr& msg);
00092   void irSensorRightCallback(const std_msgs::Float32::ConstPtr& msg);
00093   void irSensorLeftCallback(const std_msgs::Float32::ConstPtr& msg);
00094   void irSensorCRightCallback(const std_msgs::Float32::ConstPtr& msg);
00095   void irSensorCLeftCallback(const std_msgs::Float32::ConstPtr& msg);
00096   void irSensorBottomCallback(const std_msgs::Int16::ConstPtr& msg);
00097 
00098   // Odom Callback Methods
00099   void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00100 
00101   // Encoder Callback Methods
00102   void encoderLLCallback(const std_msgs::Int16::ConstPtr& msg);
00103   void encoderLRCallback(const std_msgs::Int16::ConstPtr& msg);
00104   void encoderRLCallback(const std_msgs::Int16::ConstPtr& msg);
00105   void encoderRRCallback(const std_msgs::Int16::ConstPtr& msg);
00106 
00107   // Other Sensor Callback Methods
00108   void magnetometerCallback(const geometry_msgs::Vector3::ConstPtr& msg);
00109   void gyroscopeCallback(const geometry_msgs::Vector3::ConstPtr& msg);
00110   void accelerometerCallback(const geometry_msgs::Vector3::ConstPtr& msg);
00111 
00112   // Camera Callback Modules
00113   void piCamCallback();
00114 };
00115 
00116 #endif //GUARD_PHEENO_ROBOT_H


pheeno_ros
Author(s): Zahi Kakish, Sean Wilson
autogenerated on Thu Jun 6 2019 21:26:16