2 #include "std_msgs/Float32.h" 3 #include "std_msgs/Int16.h" 4 #include "geometry_msgs/Twist.h" 5 #include "nav_msgs/Odometry.h" 26 for (
int i = 0; i < 6; i++)
32 for (
int i = 0; i < 3; i++)
44 for (
int i = 0; i < 4; i++)
159 for (
int i = 0; i < 7; i++)
168 return (count > 1) ?
true :
false;
183 if (msg->data < 1600)
300 return rand() % 10 + 1 <= 5 ? (-1 * angular) : angular;
325 angular = -1 * angular_velocity;
330 angular = angular_velocity;
341 angular = -1 * angular_velocity;
346 angular = angular_velocity;
351 angular = -1 * angular_velocity;
356 angular = angular_velocity;
360 linear = linear_velocity;
386 angular = -1 * angular_velocity;
390 angular = angular_velocity;
399 angular = -1 * angular_velocity;
403 angular = angular_velocity;
407 angular = -1 * angular_velocity;
411 angular = angular_velocity;
415 angular = random_turn_value;
418 if (angular != random_turn_value)
420 random_turn_value = angular;
bool irSensorTriggered(float sensor_limits)
void irSensorCLeftCallback(const std_msgs::Float32::ConstPtr &msg)
void accelerometerCallback(const geometry_msgs::Vector3::ConstPtr &msg)
void publish(geometry_msgs::Twist velocity)
void irSensorBottomCallback(const std_msgs::Int16::ConstPtr &msg)
std::vector< double > gyroscope_vals_
void gyroscopeCallback(const geometry_msgs::Vector3::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
PheenoRobot(std::string pheeno_name)
ros::Subscriber sub_ir_cr_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_odom_
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
void encoderRLCallback(const std_msgs::Int16::ConstPtr &msg)
void irSensorCenterCallback(const std_msgs::Float32::ConstPtr &msg)
ros::Subscriber sub_gyroscope_
std::vector< double > odom_pose_position_
ros::Subscriber sub_encoder_RL_
ros::Subscriber sub_magnetometer_
void irSensorBackCallback(const std_msgs::Float32::ConstPtr &msg)
ros::Subscriber sub_ir_left_
ros::Subscriber sub_encoder_LR_
std_msgs::Int16 ir_sensor_bottom_
std::vector< double > odom_twist_angular_
void magnetometerCallback(const geometry_msgs::Vector3::ConstPtr &msg)
ros::Subscriber sub_ir_bottom_
std::vector< double > accelerometer_vals_
std::vector< double > odom_pose_orient_
std::vector< int > encoder_vals_
ros::Subscriber sub_encoder_RR_
ros::Subscriber sub_ir_center_
ros::Subscriber sub_ir_right_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< double > odom_twist_linear_
ros::Subscriber sub_accelerometer_
void encoderLRCallback(const std_msgs::Int16::ConstPtr &msg)
ros::Subscriber sub_encoder_LL_
std::vector< double > magnetometer_vals_
ros::Publisher pub_cmd_vel_
void avoidObstaclesAngular(double &angular, double &random_turn_value, float angular_velocity=1.2, double range_to_avoid=20.0)
ros::Subscriber sub_ir_back_
ros::Subscriber sub_ir_cl_
void encoderLLCallback(const std_msgs::Int16::ConstPtr &msg)
void encoderRRCallback(const std_msgs::Int16::ConstPtr &msg)
void irSensorLeftCallback(const std_msgs::Float32::ConstPtr &msg)
double randomTurn(float angular=0.06)
void irSensorCRightCallback(const std_msgs::Float32::ConstPtr &msg)
std::vector< double > ir_sensor_vals_
std::string pheeno_namespace_id_
void irSensorRightCallback(const std_msgs::Float32::ConstPtr &msg)
void avoidObstaclesLinear(double &linear, double &angular, float angular_velocity=1.2, float linear_velocity=0.08, double range_to_avoid=20.0)