24 #include <webots_ros/set_int.h>
26 #include <webots_ros/set_float.h>
28 #include <sensor_msgs/Range.h>
31 #include <std_msgs/Float64MultiArray.h>
32 #include <std_msgs/String.h>
33 #include <std_msgs/UInt16.h>
34 #include <std_msgs/UInt8MultiArray.h>
45 #define SIMULATION 0 // for wb_robot_get_mode() function
46 #define REALITY 2 // for wb_robot_get_mode() function
47 #define TIME_STEP 32 // [ms]
50 #define NB_DIST_SENS 8
54 #define PS_RIGHT_REAR 3
55 #define PS_LEFT_REAR 4
65 #define NB_GROUND_SENS 3
87 std::vector<unsigned char>
image;
92 void psCallback(
const sensor_msgs::Range::ConstPtr &value) {
99 void gsCallback(
const sensor_msgs::Range::ConstPtr &value) {
114 ROS_INFO(
"User stopped the 'e_puck_line' node.");
134 #define LFM_FORWARD_SPEED 200
135 #define LFM_K_GS_SPEED 0.4
160 #define OAM_OBST_THRESHOLD 100
161 #define OAM_FORWARD_SPEED 150
162 #define OAM_K_PS_90 0.2
163 #define OAM_K_PS_45 0.9
164 #define OAM_K_PS_00 1.2
165 #define OAM_K_MAX_DELTAS 600
169 int Activation[] = {0, 0};
194 if (Activation[
RIGHT] > Activation[
LEFT])
245 #define LLM_THRESHOLD 800
292 #define OFM_DELTA_SPEED 150
330 #define LEM_FORWARD_SPEED 100
331 #define LEM_K_GS_SPEED 0.8
332 #define LEM_THRESHOLD 500
334 #define LEM_STATE_STANDBY 0
335 #define LEM_STATE_LOOKING_FOR_LINE 1
336 #define LEM_STATE_LINE_DETECTED 2
337 #define LEM_STATE_ON_LINE 3
340 int Side, OpSide, GS_Side, GS_OpSide;
420 int main(
int argc,
char **argv) {
430 ROS_INFO(
"Usage: $ e_puck_line [duration(seconds)].");
433 stepMax = atoll(argv[1]) * 1000 /
TIME_STEP;
434 ROS_INFO(
"Max step is %d.", stepMax);
439 signal(SIGINT,
quit);
442 std::string modelName;
456 std::cout <<
"Choose the # of the model you want to use:\n";
457 std::cin >> wantedModel;
458 if (1 <= wantedModel && wantedModel <=
count)
472 std::vector<ros::ServiceClient> enableDistSensorClient;
473 webots_ros::set_int enableDistSensorSrv;
478 ROS_ERROR(
"Failed to call service time_step to update robot's time step.");
484 sprintf(deviceName,
"ps%d", i);
485 enableDistSensorClient.push_back(n.
serviceClient<webots_ros::set_int>(modelName +
'/' + deviceName +
"/enable"));
486 enableDistSensorSrv.request.value =
step;
487 if (enableDistSensorClient[i].
call(enableDistSensorSrv) && enableDistSensorSrv.response.success) {
488 ROS_INFO(
"Device %s enabled.", deviceName);
489 std::ostringstream
s;
492 while (SubDistIr[i].getNumPublishers() == 0) {
495 if (!enableDistSensorSrv.response.success)
496 ROS_ERROR(
"Sampling period is not valid.");
497 ROS_ERROR(
"Failed to enable %s.", deviceName);
505 sprintf(deviceName,
"gs%d", i);
506 enableDistSensorClient.push_back(n.
serviceClient<webots_ros::set_int>(modelName +
'/' + deviceName +
"/enable"));
507 enableDistSensorSrv.request.value =
step;
508 if (enableDistSensorClient[i +
NB_DIST_SENS].
call(enableDistSensorSrv) && enableDistSensorSrv.response.success) {
509 ROS_INFO(
"Device %s enabled.", deviceName);
510 std::ostringstream
s;
513 while (SubGndIr[i].getNumPublishers() == 0) {
516 if (!enableDistSensorSrv.response.success)
517 ROS_ERROR(
"Sampling period is not valid.");
518 ROS_ERROR(
"Failed to enable %s.", deviceName);
524 webots_ros::set_float wheelSrv;
525 wheelSrv.request.value = INFINITY;
527 n.
serviceClient<webots_ros::set_float>(modelName +
"/left_wheel_motor/set_position");
528 leftWheelPositionClient.
call(wheelSrv);
530 n.
serviceClient<webots_ros::set_float>(modelName +
"/right_wheel_motor/set_position");
531 rightWheelPositionClient.
call(wheelSrv);
533 n.
serviceClient<webots_ros::set_float>(modelName +
"/left_wheel_motor/set_velocity");
535 n.
serviceClient<webots_ros::set_float>(modelName +
"/right_wheel_motor/set_velocity");
538 std::vector<ros::ServiceClient> setLedClient;
539 webots_ros::set_int setLedSrv;
540 sprintf(deviceName,
"led0");
541 setLedClient.push_back(n.
serviceClient<webots_ros::set_int>(modelName +
'/' + deviceName +
"/set_led"));
542 setLedSrv.request.value = 1;
543 if (setLedClient[0].
call(setLedSrv) && setLedSrv.response.success)
544 ROS_INFO(
"%s turned on!", deviceName);
546 ROS_ERROR(
"Failed to call service set_led to enable %s.", deviceName);
549 sprintf(deviceName,
"led8");
550 setLedClient.push_back(n.
serviceClient<webots_ros::set_int>(modelName +
'/' + deviceName +
"/set_led"));
551 setLedSrv.request.value = 1;
552 if (setLedClient[1].
call(setLedSrv) && setLedSrv.response.success)
553 ROS_INFO(
"%s turned on!", deviceName);
555 ROS_ERROR(
"Failed to call service set_led to enable %s.", deviceName);
570 ROS_ERROR(
"Failed to call service time_step to update robot's time step.");
573 while (nStep <= stepMax) {
577 ROS_ERROR(
"Failed to call service time_step to update robot's time step.");
639 ROS_INFO(
"OAM %d side NO_SIDE step %d LLM %d inibitA %d OFM %d LEM %d state %d oam_reset %d.",
oam_active, nStep,
642 ROS_INFO(
"OAM %d side LEFT step %d LLM %d inibitA %d OFM %d LEM %d state %d oam_reset %d.",
oam_active, nStep,
645 ROS_INFO(
"OAM %d side RIGHT step %d LLM %d inibitA %d OFM %d LEM %d state %d oam_reset %d.",
oam_active, nStep,
649 wheelSrv.request.value = (
M_PI / 1000.0) * speed[
LEFT];
650 leftWheelVelocityClient.
call(wheelSrv);
651 wheelSrv.request.value = (
M_PI / 1000.0) * speed[
RIGHT];
652 rightWheelVelocityClient.call(wheelSrv);
656 sprintf(deviceName,
"led8");
657 setLedSrv.request.value = 0;
658 if (setLedClient[1].
call(setLedSrv) && setLedSrv.response.success == 1)
659 ROS_INFO(
"%s turned off.", deviceName);
661 ROS_ERROR(
"Failed to call service set_led to enable %s.", deviceName);
664 sprintf(deviceName,
"led0");
665 setLedSrv.request.value = 0;
666 if (setLedClient[0].
call(setLedSrv) && setLedSrv.response.success == 1)
667 ROS_INFO(
"%s turned off.", deviceName);
669 ROS_ERROR(
"Failed to call service set_led to enable %s.", deviceName);
688 ROS_INFO(
"Robot's time step updated to end simulation.");
690 ROS_ERROR(
"Failed to call service time_step to end simulation.");