[Documentation] [TitleIndex] [WordIndex

Package Summary

The goto_crossing package provides a goToGoal behavior to a crossing center if the crossing has at least three frontiers and some kind of move forward behavior if it has two or less frontiers.

The goto_crossing provides a Go-To-Goal behavior to reach the center of a crossing (lama_msgs/Crossing message) for the Large Maps Framework (LaMa).

Overview

The goto_crossing provides a Go-To-Goal behavior to reach the center of a crossing (lama_msgs/Crossing message).

Can be used as a ROS node or as a class instance, as documented below.

Usage

As ROS Node

Launch the node with rosrun goto_crossing goto_crossing.

As Class Instance

To use the goto_crossing::CrossingGoer as class instance, one uses goto_crossing::CrossingGoer::goto_crossing to compute the twist necessary to reach the crossing center:

   1 #include <geometry_msgs/Twist.h>
   2 #include <goto_crossing/crossing_goer.h>
   3 #include <lama_msgs/Crossing.h>
   4 
   5 goto_crossing::CrossingGoer crossing_goer;
   6 
   7 lama_msgs::Crossing crossing;
   8 geometry_msgs::Twist twist;
   9 crossing.center.x = 0.56;
  10 crossing.center.y = 0.24;
  11 const bool goal_reached = crossing_goer.goto_crossing(crossing, twist);

To reset the integral parts of the PI-controller, use

   1 crossing_goer.resetIntegrals();

ROS API

Subscribed Topics

~<name>/crossing (lama_msgs/Crossing)

Published Topics

~<name>/cmd_vel (geometry_msgs/Twist) ~<name>/goal_reached (std_msgs/Bool)

Services

~<name>/reset_integrals (std_srvs/Empty)

Parameters

~<name>/kp_v (float) ~<name>/kp_w (float) ~<name>/ki_v (float) ~<name>/ki_w (float) ~<name>/min_linear_velocity (float) ~<name>/max_linear_velocity (float) ~<name>/min_angular_velocity (float) ~<name>/max_angular_velocity (float) ~<name>/reach_distance (float) ~<name>/dtheta_force_lef (float) ~<name>/threshold_w_only (float) ~<name>/max_sum_v (float) ~<name>/max_sum_w (float)


2019-11-09 12:42