#include "ros/ros.h"#include <webots_ros/set_int.h>#include <webots_ros/set_float.h>#include <sensor_msgs/Range.h>#include <signal.h>#include <std_msgs/Float64MultiArray.h>#include <std_msgs/String.h>#include <std_msgs/UInt16.h>#include <std_msgs/UInt8MultiArray.h>#include <cstdlib>
Go to the source code of this file.
Macros | |
| #define | BLACK 1 |
| #define | FALSE 0 |
| #define | GS_CENTER 1 |
| #define | GS_LEFT 0 |
| #define | GS_RIGHT 2 |
| #define | GS_WHITE 900 |
| #define | LEFT 0 |
| #define | LEM_FORWARD_SPEED 100 |
| #define | LEM_K_GS_SPEED 0.8 |
| #define | LEM_STATE_LINE_DETECTED 2 |
| #define | LEM_STATE_LOOKING_FOR_LINE 1 |
| #define | LEM_STATE_ON_LINE 3 |
| #define | LEM_STATE_STANDBY 0 |
| #define | LEM_THRESHOLD 500 |
| #define | LFM_FORWARD_SPEED 200 |
| #define | LFM_K_GS_SPEED 0.4 |
| #define | LLM_THRESHOLD 800 |
| #define | NB_DIST_SENS 8 |
| #define | NB_GROUND_SENS 3 |
| #define | NB_LEDS 10 |
| #define | NO_SIDE -1 |
| #define | OAM_FORWARD_SPEED 150 |
| #define | OAM_K_MAX_DELTAS 600 |
| #define | OAM_K_PS_00 1.2 |
| #define | OAM_K_PS_45 0.9 |
| #define | OAM_K_PS_90 0.2 |
| #define | OAM_OBST_THRESHOLD 100 |
| #define | OFM_DELTA_SPEED 150 |
| #define | PS_LEFT_00 7 |
| #define | PS_LEFT_45 6 |
| #define | PS_LEFT_90 5 |
| #define | PS_LEFT_REAR 4 |
| #define | PS_RIGHT_00 0 |
| #define | PS_RIGHT_45 1 |
| #define | PS_RIGHT_90 2 |
| #define | PS_RIGHT_REAR 3 |
| #define | REALITY 2 |
| #define | RIGHT 1 |
| #define | SIMULATION 0 |
| #define | TIME_STEP 32 |
| #define | TRUE 1 |
| #define | WHITE 0 |
Functions | |
| void | gsCallback (const sensor_msgs::Range::ConstPtr &value) |
| void | LineEnteringModule (int side) |
| void | LineFollowingModule (void) |
| void | LineLeavingModule (int side) |
| int | main (int argc, char **argv) |
| void | modelNameCallback (const std_msgs::String::ConstPtr &name) |
| void | ObstacleAvoidanceModule (void) |
| void | ObstacleFollowingModule (int side) |
| void | psCallback (const sensor_msgs::Range::ConstPtr &value) |
| void | quit (int sig) |
Variables | |
| double | accelerometerValues [3] = {0, 0, 0} |
| static int | count = 0 |
| static int | countDist = NB_DIST_SENS |
| static int | countGnd = NB_GROUND_SENS |
| int | curOpGsValue |
| unsigned short | gsValue [NB_GROUND_SENS] = {0, 0, 0} |
| std::vector< unsigned char > | image |
| int | lem_active |
| int | lem_black_counter |
| int | lem_reset |
| int | lem_speed [2] |
| int | lem_state |
| int | lfm_speed [2] |
| int | llm_active = FALSE |
| int | llm_inibit_ofm_speed |
| int | llm_past_side = NO_SIDE |
| static char | modelList [10][100] |
| int | oam_active |
| int | oam_reset |
| int | oam_side = NO_SIDE |
| int | oam_speed [2] |
| int | ofm_active |
| int | ofm_speed [2] |
| int | prevOpGsValue |
| const int | PS_OFFSET_REALITY [NB_DIST_SENS] = {480, 170, 320, 500, 600, 680, 210, 640} |
| const int | PS_OFFSET_SIMULATION [NB_DIST_SENS] = {300, 300, 300, 300, 300, 300, 300, 300} |
| int | psValue [NB_DIST_SENS] = {0, 0, 0, 0, 0, 0, 0, 0} |
| ros::ServiceClient | setTimeStepClient |
| webots_ros::set_int | setTimeStepSrv |
| static int | step = TIME_STEP |
| #define BLACK 1 |
Definition at line 44 of file e_puck_line.cpp.
| #define FALSE 0 |
Definition at line 39 of file e_puck_line.cpp.
| #define GS_CENTER 1 |
Definition at line 68 of file e_puck_line.cpp.
| #define GS_LEFT 0 |
Definition at line 67 of file e_puck_line.cpp.
| #define GS_RIGHT 2 |
Definition at line 69 of file e_puck_line.cpp.
| #define GS_WHITE 900 |
Definition at line 66 of file e_puck_line.cpp.
| #define LEFT 0 |
Definition at line 41 of file e_puck_line.cpp.
| #define LEM_FORWARD_SPEED 100 |
Definition at line 330 of file e_puck_line.cpp.
| #define LEM_K_GS_SPEED 0.8 |
Definition at line 331 of file e_puck_line.cpp.
| #define LEM_STATE_LINE_DETECTED 2 |
Definition at line 336 of file e_puck_line.cpp.
| #define LEM_STATE_LOOKING_FOR_LINE 1 |
Definition at line 335 of file e_puck_line.cpp.
| #define LEM_STATE_ON_LINE 3 |
Definition at line 337 of file e_puck_line.cpp.
| #define LEM_STATE_STANDBY 0 |
Definition at line 334 of file e_puck_line.cpp.
| #define LEM_THRESHOLD 500 |
Definition at line 332 of file e_puck_line.cpp.
| #define LFM_FORWARD_SPEED 200 |
Definition at line 134 of file e_puck_line.cpp.
| #define LFM_K_GS_SPEED 0.4 |
Definition at line 135 of file e_puck_line.cpp.
| #define LLM_THRESHOLD 800 |
Definition at line 245 of file e_puck_line.cpp.
| #define NB_DIST_SENS 8 |
Definition at line 50 of file e_puck_line.cpp.
| #define NB_GROUND_SENS 3 |
Definition at line 65 of file e_puck_line.cpp.
| #define NB_LEDS 10 |
Definition at line 73 of file e_puck_line.cpp.
| #define NO_SIDE -1 |
Definition at line 40 of file e_puck_line.cpp.
| #define OAM_FORWARD_SPEED 150 |
Definition at line 161 of file e_puck_line.cpp.
| #define OAM_K_MAX_DELTAS 600 |
Definition at line 165 of file e_puck_line.cpp.
| #define OAM_K_PS_00 1.2 |
Definition at line 164 of file e_puck_line.cpp.
| #define OAM_K_PS_45 0.9 |
Definition at line 163 of file e_puck_line.cpp.
| #define OAM_K_PS_90 0.2 |
Definition at line 162 of file e_puck_line.cpp.
| #define OAM_OBST_THRESHOLD 100 |
Definition at line 160 of file e_puck_line.cpp.
| #define OFM_DELTA_SPEED 150 |
Definition at line 292 of file e_puck_line.cpp.
| #define PS_LEFT_00 7 |
Definition at line 58 of file e_puck_line.cpp.
| #define PS_LEFT_45 6 |
Definition at line 57 of file e_puck_line.cpp.
| #define PS_LEFT_90 5 |
Definition at line 56 of file e_puck_line.cpp.
| #define PS_LEFT_REAR 4 |
Definition at line 55 of file e_puck_line.cpp.
| #define PS_RIGHT_00 0 |
Definition at line 51 of file e_puck_line.cpp.
| #define PS_RIGHT_45 1 |
Definition at line 52 of file e_puck_line.cpp.
| #define PS_RIGHT_90 2 |
Definition at line 53 of file e_puck_line.cpp.
| #define PS_RIGHT_REAR 3 |
Definition at line 54 of file e_puck_line.cpp.
| #define REALITY 2 |
Definition at line 46 of file e_puck_line.cpp.
| #define RIGHT 1 |
Definition at line 42 of file e_puck_line.cpp.
| #define SIMULATION 0 |
Definition at line 45 of file e_puck_line.cpp.
| #define TIME_STEP 32 |
Definition at line 47 of file e_puck_line.cpp.
| #define TRUE 1 |
Definition at line 38 of file e_puck_line.cpp.
| #define WHITE 0 |
Definition at line 43 of file e_puck_line.cpp.
| void gsCallback | ( | const sensor_msgs::Range::ConstPtr & | value | ) |
Definition at line 99 of file e_puck_line.cpp.
| void LineEnteringModule | ( | int | side | ) |
Definition at line 339 of file e_puck_line.cpp.
| void LineFollowingModule | ( | void | ) |
Definition at line 137 of file e_puck_line.cpp.
| void LineLeavingModule | ( | int | side | ) |
Definition at line 247 of file e_puck_line.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 420 of file e_puck_line.cpp.
| void modelNameCallback | ( | const std_msgs::String::ConstPtr & | name | ) |
Definition at line 105 of file e_puck_line.cpp.
| void ObstacleAvoidanceModule | ( | void | ) |
Definition at line 167 of file e_puck_line.cpp.
| void ObstacleFollowingModule | ( | int | side | ) |
Definition at line 294 of file e_puck_line.cpp.
| void psCallback | ( | const sensor_msgs::Range::ConstPtr & | value | ) |
Definition at line 92 of file e_puck_line.cpp.
| void quit | ( | int | sig | ) |
Definition at line 111 of file e_puck_line.cpp.
| double accelerometerValues[3] = {0, 0, 0} |
Definition at line 86 of file e_puck_line.cpp.
|
static |
Definition at line 82 of file e_puck_line.cpp.
|
static |
Definition at line 83 of file e_puck_line.cpp.
|
static |
Definition at line 84 of file e_puck_line.cpp.
| int curOpGsValue |
Definition at line 328 of file e_puck_line.cpp.
| unsigned short gsValue[NB_GROUND_SENS] = {0, 0, 0} |
Definition at line 70 of file e_puck_line.cpp.
| std::vector<unsigned char> image |
Definition at line 87 of file e_puck_line.cpp.
| int lem_active |
Definition at line 325 of file e_puck_line.cpp.
| int lem_black_counter |
Definition at line 327 of file e_puck_line.cpp.
| int lem_reset |
Definition at line 243 of file e_puck_line.cpp.
| int lem_speed[2] |
Definition at line 326 of file e_puck_line.cpp.
| int lem_state |
Definition at line 327 of file e_puck_line.cpp.
| int lfm_speed[2] |
Definition at line 132 of file e_puck_line.cpp.
| int llm_active = FALSE |
Definition at line 242 of file e_puck_line.cpp.
| int llm_inibit_ofm_speed |
Definition at line 242 of file e_puck_line.cpp.
| int llm_past_side = NO_SIDE |
Definition at line 242 of file e_puck_line.cpp.
|
static |
Definition at line 81 of file e_puck_line.cpp.
| int oam_active |
Definition at line 156 of file e_puck_line.cpp.
| int oam_reset |
Definition at line 156 of file e_puck_line.cpp.
| int oam_side = NO_SIDE |
Definition at line 158 of file e_puck_line.cpp.
| int oam_speed[2] |
Definition at line 157 of file e_puck_line.cpp.
| int ofm_active |
Definition at line 289 of file e_puck_line.cpp.
| int ofm_speed[2] |
Definition at line 290 of file e_puck_line.cpp.
| int prevOpGsValue |
Definition at line 328 of file e_puck_line.cpp.
| const int PS_OFFSET_REALITY[NB_DIST_SENS] = {480, 170, 320, 500, 600, 680, 210, 640} |
Definition at line 62 of file e_puck_line.cpp.
| const int PS_OFFSET_SIMULATION[NB_DIST_SENS] = {300, 300, 300, 300, 300, 300, 300, 300} |
Definition at line 61 of file e_puck_line.cpp.
| int psValue[NB_DIST_SENS] = {0, 0, 0, 0, 0, 0, 0, 0} |
Definition at line 60 of file e_puck_line.cpp.
| ros::ServiceClient setTimeStepClient |
Definition at line 89 of file e_puck_line.cpp.
| webots_ros::set_int setTimeStepSrv |
Definition at line 90 of file e_puck_line.cpp.
|
static |
Definition at line 85 of file e_puck_line.cpp.