#include <stdlib.h>#include <stdio.h>#include <math.h>#include <string.h>#include <unistd.h>#include <ros/ros.h>#include <ros/time.h>#include <std_msgs/String.h>#include <std_msgs/Float32.h>#include <std_msgs/Int8.h>#include <std_msgs/Int16.h>#include <std_msgs/Bool.h>#include <std_msgs/Empty.h>#include <geometry_msgs/Point32.h>#include <geometry_msgs/Pose2D.h>
Go to the source code of this file.
Defines | |
| #define | PI 3.1415 | 
Functions | |
| void | batteryPowerCB (const std_msgs::Float32::ConstPtr &battery) | 
| void | calcOdometryDist (float dist, float alfa) | 
| void | enable_encodersRead () | 
| void | enable_encodersReset () | 
| void | enable_infoData () | 
| void | enable_stopMotors () | 
| void | encoder1_readCB (const std_msgs::Int16::ConstPtr &pulses1) | 
| void | encoder2_readCB (const std_msgs::Int16::ConstPtr &pulses2) | 
| int | encodersRead () | 
| void | firmwareVersionCB (const std_msgs::Float32::ConstPtr &firmwareV) | 
| void | goTo (int x, int y, float teta, int xFinal, int yFinal, float tetaFinal) | 
| int | main (int argc, char **argv) | 
| float | median (int n, float x[]) | 
| void | move (float dist, int speed1, int speed2) | 
| void | moveMotors (int speed1, int speed2, int way) | 
| bool | powerCheck (float batteryValue) | 
| float | pulse2dist (int pulse) | 
| void | reactiveNavigation () | 
| void | rotate (float angle, int speed) | 
| void | sonar1CB (const std_msgs::Int16::ConstPtr &sonar1) | 
| void | sonar2CB (const std_msgs::Int16::ConstPtr &sonar2) | 
| void | sonar3CB (const std_msgs::Int16::ConstPtr &sonar3) | 
| void | squareTest (int side_width, int way, int cycles) | 
| void | stepTest () | 
| void | temperatureCB (const std_msgs::Int8::ConstPtr &temp) | 
Variables | |
| float | alfa = 0 | 
| int | counter1 = 0 | 
| int | counter2 = 0 | 
| int | counter3 = 0 | 
| float | dist = 0 | 
| int | encoderRead1 | 
| int | encoderRead2 | 
| float | info_battery | 
| float | info_driverF | 
| int | info_temp | 
| float | phi = 0 | 
| ros::Publisher | pub_encodersRead | 
| ros::Publisher | pub_encodersReset | 
| ros::Publisher | pub_moveMotors | 
| ros::Publisher | pub_odometry | 
| ros::Publisher | pub_sonars | 
| ros::Publisher | pub_stopMotors | 
| ros::Publisher | pub_traxbotInfo | 
| float | r_robot = 185.0 | 
| float | r_wheel = 39.0 | 
| int | range_msg1 | 
| int | range_msg2 | 
| int | range_msg3 | 
| int | reactiveRange = 35 | 
| int | samples = 10 | 
| float | sonar1Samples [10] | 
| float | sonar2Samples [10] | 
| float | sonar3Samples [10] | 
| ros::Subscriber | sub_batteryPower | 
| ros::Subscriber | sub_driverFirmware | 
| ros::Subscriber | sub_driverTemperature | 
| ros::Subscriber | sub_encoderRead1 | 
| ros::Subscriber | sub_encoderRead2 | 
| ros::Subscriber | sub_range1 | 
| ros::Subscriber | sub_range2 | 
| ros::Subscriber | sub_range3 | 
| float | teta = 0 | 
| float | tetaFinal = 0 | 
| float | tetaTemp = 0 | 
| int | vMove = 25 | 
| int | vRotate = 20 | 
| int | x = 0 | 
| int | xFinal = 0 | 
| int | xTemp = 0 | 
| int | y = 0 | 
| int | yFinal = 0 | 
| int | yTemp = 0 | 
| #define PI 3.1415 | 
Definition at line 65 of file traxbot_driverTest.cpp.
| void batteryPowerCB | ( | const std_msgs::Float32::ConstPtr & | battery | ) | 
Definition at line 196 of file traxbot_driverTest.cpp.
| void calcOdometryDist | ( | float | dist, | 
| float | alfa | ||
| ) | 
Definition at line 322 of file traxbot_driverTest.cpp.
| void enable_encodersRead | ( | ) | 
Definition at line 148 of file traxbot_driverTest.cpp.
| void enable_encodersReset | ( | ) | 
Definition at line 157 of file traxbot_driverTest.cpp.
| void enable_infoData | ( | ) | 
Definition at line 175 of file traxbot_driverTest.cpp.
| void enable_stopMotors | ( | ) | 
Definition at line 166 of file traxbot_driverTest.cpp.
| void encoder1_readCB | ( | const std_msgs::Int16::ConstPtr & | pulses1 | ) | 
Definition at line 184 of file traxbot_driverTest.cpp.
| void encoder2_readCB | ( | const std_msgs::Int16::ConstPtr & | pulses2 | ) | 
Definition at line 190 of file traxbot_driverTest.cpp.
| int encodersRead | ( | ) | 
Definition at line 310 of file traxbot_driverTest.cpp.
| void firmwareVersionCB | ( | const std_msgs::Float32::ConstPtr & | firmwareV | ) | 
Definition at line 201 of file traxbot_driverTest.cpp.
| void goTo | ( | int | x, | 
| int | y, | ||
| float | teta, | ||
| int | xFinal, | ||
| int | yFinal, | ||
| float | tetaFinal | ||
| ) | 
Definition at line 472 of file traxbot_driverTest.cpp.
| int main | ( | int | argc, | 
| char ** | argv | ||
| ) | 
Definition at line 621 of file traxbot_driverTest.cpp.
| float median | ( | int | n, | 
| float | x[] | ||
| ) | 
Definition at line 123 of file traxbot_driverTest.cpp.
| void move | ( | float | dist, | 
| int | speed1, | ||
| int | speed2 | ||
| ) | 
Definition at line 353 of file traxbot_driverTest.cpp.
| void moveMotors | ( | int | speed1, | 
| int | speed2, | ||
| int | way | ||
| ) | 
Definition at line 275 of file traxbot_driverTest.cpp.
| bool powerCheck | ( | float | batteryValue | ) | 
Definition at line 289 of file traxbot_driverTest.cpp.
| float pulse2dist | ( | int | pulse | ) | 
Definition at line 303 of file traxbot_driverTest.cpp.
| void reactiveNavigation | ( | ) | 
Definition at line 553 of file traxbot_driverTest.cpp.
| void rotate | ( | float | angle, | 
| int | speed | ||
| ) | 
Definition at line 399 of file traxbot_driverTest.cpp.
| void sonar1CB | ( | const std_msgs::Int16::ConstPtr & | sonar1 | ) | 
Definition at line 211 of file traxbot_driverTest.cpp.
| void sonar2CB | ( | const std_msgs::Int16::ConstPtr & | sonar2 | ) | 
Definition at line 232 of file traxbot_driverTest.cpp.
| void sonar3CB | ( | const std_msgs::Int16::ConstPtr & | sonar3 | ) | 
Definition at line 252 of file traxbot_driverTest.cpp.
| void squareTest | ( | int | side_width, | 
| int | way, | ||
| int | cycles | ||
| ) | 
Definition at line 513 of file traxbot_driverTest.cpp.
| void stepTest | ( | ) | 
Definition at line 610 of file traxbot_driverTest.cpp.
| void temperatureCB | ( | const std_msgs::Int8::ConstPtr & | temp | ) | 
Definition at line 206 of file traxbot_driverTest.cpp.
| float alfa = 0 | 
Definition at line 76 of file traxbot_driverTest.cpp.
| int counter1 = 0 | 
Definition at line 87 of file traxbot_driverTest.cpp.
| int counter2 = 0 | 
Definition at line 87 of file traxbot_driverTest.cpp.
| int counter3 = 0 | 
Definition at line 87 of file traxbot_driverTest.cpp.
| float dist = 0 | 
Definition at line 76 of file traxbot_driverTest.cpp.
| int encoderRead1 | 
Definition at line 68 of file traxbot_driverTest.cpp.
| int encoderRead2 | 
Definition at line 68 of file traxbot_driverTest.cpp.
| float info_battery | 
Definition at line 67 of file traxbot_driverTest.cpp.
| float info_driverF | 
Definition at line 67 of file traxbot_driverTest.cpp.
| int info_temp | 
Definition at line 68 of file traxbot_driverTest.cpp.
| float phi = 0 | 
Definition at line 76 of file traxbot_driverTest.cpp.
Definition at line 100 of file traxbot_driverTest.cpp.
Definition at line 99 of file traxbot_driverTest.cpp.
Definition at line 97 of file traxbot_driverTest.cpp.
Definition at line 103 of file traxbot_driverTest.cpp.
Definition at line 93 of file traxbot_driverTest.cpp.
Definition at line 98 of file traxbot_driverTest.cpp.
Definition at line 92 of file traxbot_driverTest.cpp.
| float r_robot = 185.0 | 
Definition at line 78 of file traxbot_driverTest.cpp.
| float r_wheel = 39.0 | 
Definition at line 78 of file traxbot_driverTest.cpp.
| int range_msg1 | 
Definition at line 68 of file traxbot_driverTest.cpp.
| int range_msg2 | 
Definition at line 68 of file traxbot_driverTest.cpp.
| int range_msg3 | 
Definition at line 68 of file traxbot_driverTest.cpp.
| int reactiveRange = 35 | 
Definition at line 83 of file traxbot_driverTest.cpp.
| int samples = 10 | 
Definition at line 85 of file traxbot_driverTest.cpp.
| float sonar1Samples[10] | 
Definition at line 86 of file traxbot_driverTest.cpp.
| float sonar2Samples[10] | 
Definition at line 86 of file traxbot_driverTest.cpp.
| float sonar3Samples[10] | 
Definition at line 86 of file traxbot_driverTest.cpp.
Definition at line 110 of file traxbot_driverTest.cpp.
Definition at line 109 of file traxbot_driverTest.cpp.
Definition at line 111 of file traxbot_driverTest.cpp.
Definition at line 114 of file traxbot_driverTest.cpp.
Definition at line 115 of file traxbot_driverTest.cpp.
Definition at line 118 of file traxbot_driverTest.cpp.
Definition at line 119 of file traxbot_driverTest.cpp.
Definition at line 120 of file traxbot_driverTest.cpp.
| float teta = 0 | 
Definition at line 71 of file traxbot_driverTest.cpp.
| float tetaFinal = 0 | 
Definition at line 74 of file traxbot_driverTest.cpp.
| float tetaTemp = 0 | 
Definition at line 71 of file traxbot_driverTest.cpp.
| int vMove = 25 | 
Definition at line 80 of file traxbot_driverTest.cpp.
| int vRotate = 20 | 
Definition at line 80 of file traxbot_driverTest.cpp.
| int x = 0 | 
Definition at line 70 of file traxbot_driverTest.cpp.
| int xFinal = 0 | 
Definition at line 73 of file traxbot_driverTest.cpp.
| int xTemp = 0 | 
Definition at line 70 of file traxbot_driverTest.cpp.
| int y = 0 | 
Definition at line 70 of file traxbot_driverTest.cpp.
| int yFinal = 0 | 
Definition at line 73 of file traxbot_driverTest.cpp.
| int yTemp = 0 | 
Definition at line 70 of file traxbot_driverTest.cpp.