From 0e91caf1139b180d716dc1ea71657ee0f6efe21c Mon Sep 17 00:00:00 2001 From: Justin CHARMETANT Date: Sat, 9 Nov 2024 11:27:08 +0100 Subject: [PATCH] Add documentation and correct values for the thresholds in autopilot.cpp --- src/autopilot.cpp | 31 ++++++++++++++++++++++--------- 1 file changed, 22 insertions(+), 9 deletions(-) diff --git a/src/autopilot.cpp b/src/autopilot.cpp index 841dd3f..439d293 100644 --- a/src/autopilot.cpp +++ b/src/autopilot.cpp @@ -1,5 +1,15 @@ +/** + * \file autopilot.cpp + * \brief Autopilot of a turtlebot3 robot until it mapped most of its environment. + * \author Justin CHARMETANT, Maxime LOBIETTI, Gauthier BOULA DE MAREUIL + * \version 0.1 + * \date 07/11/2024 + * + * Program that controls a turtlebot3 burger robot using the bringup and slam nodes from ROS noetic. + * +*/ + #include -#include "std_msgs/String.h" #include #include #include @@ -10,8 +20,8 @@ bool isCollisionDetected = false; bool isFinished = false; int angleDetection = 15; double distThreshold = 0.3; -float batThreshold = 10; -double entroThreshold = 100000000; +float batThreshold = 10; // We want the voltage of the battery to be above 10V to run the robot. +double entroThreshold = 0.1; // We want an entropy below 0.1 to stop the program. // Function to run when receive data from the subscribed Lidar void scanCallback(const sensor_msgs::LaserScan::ConstPtr& data) // @@ -24,7 +34,7 @@ void scanCallback(const sensor_msgs::LaserScan::ConstPtr& data) // double firstVal = data->ranges[i]; double lastVal = data->ranges[data->ranges.size()-i-1]; - // Check if one of the data is below the threshold + // Check if one of the data is below the threshold distance if (lastVal entroThreshold){ + if (entropy.data < entroThreshold){ isFinished = true; } } +// Function to run when receive data from the subscribed battery_state topic from SLAM void batteryCallback(const sensor_msgs::BatteryState::ConstPtr& bat) { if (bat->voltage < batThreshold){ @@ -51,7 +63,8 @@ void batteryCallback(const sensor_msgs::BatteryState::ConstPtr& bat) } } - + + int main(int argc, char** argv) { ros::init(argc,argv, "autopilot"); @@ -75,7 +88,7 @@ int main(int argc, char** argv) { geometry_msgs::Twist msg; - + // If isFinished is true, it means either the map is full or the battery is low, therefore we stop moving if (!isFinished){ if (isCollisionDetected){ msg.angular.z = 1; @@ -84,7 +97,7 @@ int main(int argc, char** argv) msg.linear.x = 1; } } - + cmdVelPub.publish(msg); ros::spinOnce(); loopRate.sleep();