Public Member Functions | Private Member Functions | Private Attributes
goto_crossing::CrossingGoer Class Reference

#include <crossing_goer.h>

List of all members.

Public Member Functions

void callback_goto_crossing (const lama_msgs::Crossing &crossing)
 CrossingGoer ()
bool goto_crossing (const lama_msgs::Crossing &crossing, geometry_msgs::Twist &twist)
void resetIntegrals ()

Private Member Functions

bool callback_resetIntegrals (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool goToGoal (const geometry_msgs::Point &goal, geometry_msgs::Twist &twist)

Private Attributes

double dtheta_force_left_
ros::Publisher goal_reached_publisher_
double ki_v_
 Integral gain for the linear velocity (s^-2).
double ki_w_
 Integral gain for the angular velocity (s^-2).
double kp_v_
 Proportional gain for the linear velocity (s^-1).
double kp_w_
 Proportional gain for the angular velocity (s^-1).
ros::Time last_t_
double max_angular_velocity_
double max_linear_velocity_
double max_sum_v_
 Anti wind-up for sum_v_ (m.s).
double max_sum_w_
 Anti wind-up for sum_w_ (rad.s).
double min_angular_velocity_
 Minimum angular set velocity (rad.s^-1), used if the integral gain is 0.
double min_linear_velocity_
 Minimum linear set velocity (m.s^-1), used if the integral gain is 0.
ros::NodeHandle nh_
double reach_distance_
 Goal is reached if closer than this (m).
ros::ServiceServer reset_integral_server_
double sum_v_
 Integral of linear error (m.s).
double sum_w_
 Integral of angular error (rad.s).
double threshold_w_only_
 If dtheta is greater than this, only turn, do not go forward (rad).
ros::Publisher twist_publisher_

Detailed Description

Definition at line 19 of file crossing_goer.h.


Constructor & Destructor Documentation

Definition at line 6 of file crossing_goer.cpp.


Member Function Documentation

void goto_crossing::CrossingGoer::callback_goto_crossing ( const lama_msgs::Crossing &  crossing)

Definition at line 110 of file crossing_goer.cpp.

bool goto_crossing::CrossingGoer::callback_resetIntegrals ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [private]

Definition at line 122 of file crossing_goer.cpp.

bool goto_crossing::CrossingGoer::goto_crossing ( const lama_msgs::Crossing &  crossing,
geometry_msgs::Twist &  twist 
)

Definition at line 52 of file crossing_goer.cpp.

bool goto_crossing::CrossingGoer::goToGoal ( const geometry_msgs::Point goal,
geometry_msgs::Twist &  twist 
) [private]

Definition at line 135 of file crossing_goer.cpp.

Definition at line 28 of file crossing_goer.h.


Member Data Documentation

If the goal is behind the robot, force the robot to turn left if the goal angle is within [pi - dtheta_force_left_, pi], even if the angle difference would tell that we should turn right. This is to avoid instability in the case that the angle would oscillate around pi. (rad)

Definition at line 47 of file crossing_goer.h.

Definition at line 58 of file crossing_goer.h.

Integral gain for the linear velocity (s^-2).

Definition at line 38 of file crossing_goer.h.

Integral gain for the angular velocity (s^-2).

Definition at line 39 of file crossing_goer.h.

Proportional gain for the linear velocity (s^-1).

Definition at line 36 of file crossing_goer.h.

Proportional gain for the angular velocity (s^-1).

Definition at line 37 of file crossing_goer.h.

Definition at line 60 of file crossing_goer.h.

maximum angular set velocity (rad.s^-1). if set to 0, the angular velocity is not throttled.

Definition at line 44 of file crossing_goer.h.

Maximum linear set velocity (m.s^-1). If set to 0, the velocity is not throttled.

Definition at line 41 of file crossing_goer.h.

Anti wind-up for sum_v_ (m.s).

Definition at line 52 of file crossing_goer.h.

Anti wind-up for sum_w_ (rad.s).

Definition at line 53 of file crossing_goer.h.

Minimum angular set velocity (rad.s^-1), used if the integral gain is 0.

Definition at line 43 of file crossing_goer.h.

Minimum linear set velocity (m.s^-1), used if the integral gain is 0.

Definition at line 40 of file crossing_goer.h.

Definition at line 56 of file crossing_goer.h.

Goal is reached if closer than this (m).

Definition at line 46 of file crossing_goer.h.

Definition at line 59 of file crossing_goer.h.

Integral of linear error (m.s).

Definition at line 61 of file crossing_goer.h.

Integral of angular error (rad.s).

Definition at line 62 of file crossing_goer.h.

If dtheta is greater than this, only turn, do not go forward (rad).

Definition at line 51 of file crossing_goer.h.

Definition at line 57 of file crossing_goer.h.


The documentation for this class was generated from the following files:


goto_crossing
Author(s): Gaƫl Ecorchard
autogenerated on Thu Jun 6 2019 22:02:00