Public Member Functions | |
void | AllState () |
Actions performed in all states. | |
void | AnalyseCB () |
int | CalculateDirectionSpeed (Waypoint target_position) |
Calcula el sentido de movimiento de una ruta, dependiendo de la posición inicial y el ángulo del robot. | |
int | CalculateDirectionSpeed (geometry_msgs::Pose2D target_position) |
Calcula el sentido de movimiento de una ruta, dependiendo de la posición inicial y el ángulo del robot. | |
void | CancelPath () |
int | CheckOdomReceive () |
void | ControlThread () |
All core component functionality is contained in this thread. | |
double | Dist (double x1, double y1, double x2, double y2) |
obtains distance between points p1 and p2 | |
double | DistP2S (geometry_msgs::Pose2D current_position, Waypoint s0, Waypoint s1, Waypoint *Pb) |
obtains distance between the current position and segment s0->s1, and returns the point Return: the shortest distance from p to s (utm points) and the point of the segment that gives the shortest distance | |
double | Dot2 (double x1, double y1, double x2, double y2) |
Obtains vector cross product w x v. | |
void | EmergencyState () |
Actions performed on the emergency state. | |
void | executeCB (const planner_msgs::GoToGoalConstPtr &goal) |
void | FailureState () |
Actions performed on Failure state. | |
void | GoalCB () |
void | InitState () |
Actions performed on initial state. | |
ReturnValue | MergePath () |
void | OdomCallback (const nav_msgs::Odometry::ConstPtr &odom_value) |
ReturnValue | PointDlh (geometry_msgs::Pose2D current_position, geometry_msgs::Pose2D *wp) |
Returns a point in a distance dlookahead on the path. | |
void | PreemptCB () |
int | PurePursuit () |
High level control loop in cartesian coordinates obtains desiredSpeedMps and desiredPhiEffort according to the robot location and the path defined by the waypoints. | |
purepursuit_planner_node (ros::NodeHandle h) | |
int | ReadAndPublish () |
void | ReadyState () |
Actions performed on ready state. | |
void | ROSSetup () |
Setups ROS' stuff. | |
bool | SetLaserBack () |
bool | SetLaserFront () |
void | SetRobotSpeed (double speed, double angle) |
ReturnValue | Setup () |
void | ShutDownState () |
void | StandbyState () |
Actions performed on standby state. | |
ReturnValue | Start () |
Start Controller. | |
ReturnValue | Stop () |
Stop Controller. | |
void | UpdateLookAhead () |
Updates (little by little) the variable lookahead depending of the current velocity. | |
~purepursuit_planner_node () | |
Private Attributes | |
actionlib::SimpleActionServer < planner_msgs::GoToAction > | action_server_goto |
bool | bCancel |
Flag to cancel the following path. | |
bool | bEnabled |
Flag to enable/disable the motion. | |
std::string | cmd_topic_vel_ |
Topic name to publish the vel & pos commands. | |
double | d_dist_wheel_to_center_ |
Distance from the robot center to the wheel's center. | |
double | d_lookahear_max_ |
double | d_lookahear_min_ |
Lookahead bounds. | |
double | desired_freq_ |
double | dLinearSpeed |
current robot's linear speed | |
double | dLookAhead |
Variable lookahead. | |
planner_msgs::GoToFeedback | goto_feedback |
planner_msgs::GoToGoal | goto_goal |
planner_msgs::GoToResult | goto_result |
double | Kr |
constant for Purepursuit | |
ros::Time | last_command_time |
Saves the time whenever receives a command msg and a transform between map and base link (if configured) | |
ros::Time | last_map_time |
tf::TransformListener | listener |
double | max_odom_freq |
double | max_speed_ |
Max allowed speed. | |
double | min_odom_freq |
Diagnostics min & max odometry freq. | |
std::string | name_sc_enable_back_laser_ |
std::string | name_sc_enable_front_laser_ |
service name to enable disable lasers | |
ros::NodeHandle | node_handle_ |
ros::Subscriber | odom_sub_ |
it subscribes to /odom | |
std::string | odom_topic_ |
Topic name to read the odometry from. | |
nav_msgs::Odometry | odometry_robot |
current robot's odometry | |
Path | pathCurrent |
Object with the current path that the robot is following. | |
Path | pathFilling |
Object with the path that is being filled. | |
geometry_msgs::Pose2D | pose2d_robot |
current robot's position | |
std::string | position_source_ |
Mode for reading the position of the robot ("ODOM", "MAP") | |
ros::NodeHandle | private_node_handle_ |
queue< Path > | qPath |
Vector with next paths to follow. | |
ros::ServiceClient | sc_enable_back_laser_ |
Service to enable/disable back laser. | |
ros::ServiceClient | sc_enable_front_laser_ |
Service to enable/disable front laser. | |
ros::Publisher | status_pub_ |
ros::Publisher | tranform_map_pub_ |
publish the transformation between map->base_link | |
tf::StampedTransform | transform |
unsigned int | ui_position_source |
Mode in numeric format. | |
diagnostic_updater::Updater | updater_diagnostic |
General status diagnostic updater. | |
diagnostic_updater::TopicDiagnostic * | updater_diagnostic_odom |
Diagnostic to control the frequency of the published odom. | |
ros::Publisher | vel_pub_ |
Definition at line 675 of file purepursuit_planner.cpp.
Definition at line 758 of file purepursuit_planner.cpp.
purepursuit_planner_node::~purepursuit_planner_node | ( | ) | [inline] |
Definition at line 779 of file purepursuit_planner.cpp.
void purepursuit_planner_node::AllState | ( | ) | [inline, virtual] |
Actions performed in all states.
Actions performed on all states.
Reimplemented from Component.
Definition at line 1414 of file purepursuit_planner.cpp.
void purepursuit_planner_node::AnalyseCB | ( | ) | [inline] |
Checks the status. (ActionServer)
Definition at line 1735 of file purepursuit_planner.cpp.
int purepursuit_planner_node::CalculateDirectionSpeed | ( | Waypoint | target_position | ) | [inline] |
Calcula el sentido de movimiento de una ruta, dependiendo de la posición inicial y el ángulo del robot.
Definition at line 1493 of file purepursuit_planner.cpp.
int purepursuit_planner_node::CalculateDirectionSpeed | ( | geometry_msgs::Pose2D | target_position | ) | [inline] |
Calcula el sentido de movimiento de una ruta, dependiendo de la posición inicial y el ángulo del robot.
Definition at line 1568 of file purepursuit_planner.cpp.
void purepursuit_planner_node::CancelPath | ( | ) | [inline] |
Removes all the waypoints introduced in the system
Definition at line 1357 of file purepursuit_planner.cpp.
int purepursuit_planner_node::CheckOdomReceive | ( | ) | [inline] |
Checks whether or not it's receiving odom values and/or map transformations
Definition at line 1469 of file purepursuit_planner.cpp.
void purepursuit_planner_node::ControlThread | ( | ) | [inline, virtual] |
All core component functionality is contained in this thread.
All core component functionality is contained in this thread. All of the Component component state machine code can be found here.
Reimplemented from Component.
Definition at line 908 of file purepursuit_planner.cpp.
double purepursuit_planner_node::Dist | ( | double | x1, |
double | y1, | ||
double | x2, | ||
double | y2 | ||
) | [inline] |
obtains distance between points p1 and p2
Definition at line 1069 of file purepursuit_planner.cpp.
double purepursuit_planner_node::DistP2S | ( | geometry_msgs::Pose2D | current_position, |
Waypoint | s0, | ||
Waypoint | s1, | ||
Waypoint * | Pb | ||
) | [inline] |
obtains distance between the current position and segment s0->s1, and returns the point Return: the shortest distance from p to s (utm points) and the point of the segment that gives the shortest distance
Definition at line 1080 of file purepursuit_planner.cpp.
double purepursuit_planner_node::Dot2 | ( | double | x1, |
double | y1, | ||
double | x2, | ||
double | y2 | ||
) | [inline] |
Obtains vector cross product w x v.
Definition at line 1061 of file purepursuit_planner.cpp.
void purepursuit_planner_node::EmergencyState | ( | ) | [inline, virtual] |
Actions performed on the emergency state.
Actions performed on emergency state.
Reimplemented from Component.
Definition at line 1398 of file purepursuit_planner.cpp.
void purepursuit_planner_node::executeCB | ( | const planner_msgs::GoToGoalConstPtr & | goal | ) | [inline] |
Definition at line 1483 of file purepursuit_planner.cpp.
void purepursuit_planner_node::FailureState | ( | ) | [inline, virtual] |
Actions performed on Failure state.
Actions performed on failure state.
Reimplemented from Component.
Definition at line 1408 of file purepursuit_planner.cpp.
void purepursuit_planner_node::GoalCB | ( | ) | [inline] |
Called when receiving a new target. (ActionServer)
Definition at line 1717 of file purepursuit_planner.cpp.
void purepursuit_planner_node::InitState | ( | ) | [inline, virtual] |
Actions performed on initial state.
Reimplemented from Component.
Definition at line 959 of file purepursuit_planner.cpp.
ReturnValue purepursuit_planner_node::MergePath | ( | ) | [inline] |
Definition at line 1641 of file purepursuit_planner.cpp.
void purepursuit_planner_node::OdomCallback | ( | const nav_msgs::Odometry::ConstPtr & | odom_value | ) | [inline] |
Receives odom values
Definition at line 1445 of file purepursuit_planner.cpp.
ReturnValue purepursuit_planner_node::PointDlh | ( | geometry_msgs::Pose2D | current_position, |
geometry_msgs::Pose2D * | wp | ||
) | [inline] |
Returns a point in a distance dlookahead on the path.
Definition at line 1125 of file purepursuit_planner.cpp.
void purepursuit_planner_node::PreemptCB | ( | ) | [inline] |
Called to cancel or replace current mision. (ActionServer)
Definition at line 1727 of file purepursuit_planner.cpp.
int purepursuit_planner_node::PurePursuit | ( | ) | [inline] |
High level control loop in cartesian coordinates obtains desiredSpeedMps and desiredPhiEffort according to the robot location and the path defined by the waypoints.
Definition at line 1231 of file purepursuit_planner.cpp.
int purepursuit_planner_node::ReadAndPublish | ( | ) | [inline] |
Reads data a publish several info into different topics
Definition at line 867 of file purepursuit_planner.cpp.
void purepursuit_planner_node::ReadyState | ( | ) | [inline, virtual] |
Actions performed on ready state.
Reimplemented from Component.
Definition at line 992 of file purepursuit_planner.cpp.
oid purepursuit_planner_node::ROSSetup | ( | ) | [inline] |
Setups ROS' stuff.
Definition at line 786 of file purepursuit_planner.cpp.
void purepursuit_planner_node::SetLaserBack | ( | ) | [inline] |
Disables laser front, enables laser back
Definition at line 1769 of file purepursuit_planner.cpp.
void purepursuit_planner_node::SetLaserFront | ( | ) | [inline] |
Disables laser back, enables laser front
Definition at line 1754 of file purepursuit_planner.cpp.
void purepursuit_planner_node::SetRobotSpeed | ( | double | speed, |
double | angle | ||
) | [inline] |
Definition at line 1372 of file purepursuit_planner.cpp.
ReturnValue purepursuit_planner_node::Setup | ( | ) | [inline, virtual] |
Configures and initializes the component
Configures and initializes the component
Reimplemented from Component.
Definition at line 848 of file purepursuit_planner.cpp.
void purepursuit_planner_node::ShutDownState | ( | ) | [inline] |
Definition at line 1388 of file purepursuit_planner.cpp.
void purepursuit_planner_node::StandbyState | ( | ) | [inline, virtual] |
Actions performed on standby state.
Actions performed on Standby state.
Reimplemented from Component.
Definition at line 975 of file purepursuit_planner.cpp.
ReturnValue purepursuit_planner_node::Start | ( | ) | [inline, virtual] |
Start Controller.
Reimplemented from Component.
Definition at line 877 of file purepursuit_planner.cpp.
ReturnValue purepursuit_planner_node::Stop | ( | ) | [inline, virtual] |
Stop Controller.
Reimplemented from Component.
Definition at line 892 of file purepursuit_planner.cpp.
void purepursuit_planner_node::UpdateLookAhead | ( | ) | [inline] |
Updates (little by little) the variable lookahead depending of the current velocity.
Definition at line 1037 of file purepursuit_planner.cpp.
actionlib::SimpleActionServer<planner_msgs::GoToAction> purepursuit_planner_node::action_server_goto [private] |
Definition at line 738 of file purepursuit_planner.cpp.
bool purepursuit_planner_node::bCancel [private] |
Flag to cancel the following path.
Definition at line 708 of file purepursuit_planner.cpp.
bool purepursuit_planner_node::bEnabled [private] |
Flag to enable/disable the motion.
Definition at line 706 of file purepursuit_planner.cpp.
std::string purepursuit_planner_node::cmd_topic_vel_ [private] |
Topic name to publish the vel & pos commands.
Definition at line 727 of file purepursuit_planner.cpp.
double purepursuit_planner_node::d_dist_wheel_to_center_ [private] |
Distance from the robot center to the wheel's center.
Definition at line 702 of file purepursuit_planner.cpp.
double purepursuit_planner_node::d_lookahear_max_ [private] |
Definition at line 700 of file purepursuit_planner.cpp.
double purepursuit_planner_node::d_lookahear_min_ [private] |
Lookahead bounds.
Definition at line 700 of file purepursuit_planner.cpp.
double purepursuit_planner_node::desired_freq_ [private] |
Definition at line 681 of file purepursuit_planner.cpp.
double purepursuit_planner_node::dLinearSpeed [private] |
current robot's linear speed
Definition at line 698 of file purepursuit_planner.cpp.
double purepursuit_planner_node::dLookAhead [private] |
Variable lookahead.
Definition at line 686 of file purepursuit_planner.cpp.
planner_msgs::GoToFeedback purepursuit_planner_node::goto_feedback [private] |
Definition at line 739 of file purepursuit_planner.cpp.
planner_msgs::GoToGoal purepursuit_planner_node::goto_goal [private] |
Definition at line 741 of file purepursuit_planner.cpp.
planner_msgs::GoToResult purepursuit_planner_node::goto_result [private] |
Definition at line 740 of file purepursuit_planner.cpp.
double purepursuit_planner_node::Kr [private] |
constant for Purepursuit
Definition at line 683 of file purepursuit_planner.cpp.
Saves the time whenever receives a command msg and a transform between map and base link (if configured)
Definition at line 736 of file purepursuit_planner.cpp.
Definition at line 736 of file purepursuit_planner.cpp.
Definition at line 743 of file purepursuit_planner.cpp.
double purepursuit_planner_node::max_odom_freq [private] |
Definition at line 734 of file purepursuit_planner.cpp.
double purepursuit_planner_node::max_speed_ [private] |
Max allowed speed.
Definition at line 704 of file purepursuit_planner.cpp.
double purepursuit_planner_node::min_odom_freq [private] |
Diagnostics min & max odometry freq.
Definition at line 734 of file purepursuit_planner.cpp.
std::string purepursuit_planner_node::name_sc_enable_back_laser_ [private] |
Definition at line 747 of file purepursuit_planner.cpp.
std::string purepursuit_planner_node::name_sc_enable_front_laser_ [private] |
service name to enable disable lasers
Definition at line 747 of file purepursuit_planner.cpp.
Definition at line 679 of file purepursuit_planner.cpp.
it subscribes to /odom
Definition at line 723 of file purepursuit_planner.cpp.
std::string purepursuit_planner_node::odom_topic_ [private] |
Topic name to read the odometry from.
Definition at line 725 of file purepursuit_planner.cpp.
nav_msgs::Odometry purepursuit_planner_node::odometry_robot [private] |
current robot's odometry
Definition at line 696 of file purepursuit_planner.cpp.
Path purepursuit_planner_node::pathCurrent [private] |
Object with the current path that the robot is following.
Definition at line 688 of file purepursuit_planner.cpp.
Path purepursuit_planner_node::pathFilling [private] |
Object with the path that is being filled.
Definition at line 690 of file purepursuit_planner.cpp.
geometry_msgs::Pose2D purepursuit_planner_node::pose2d_robot [private] |
current robot's position
Definition at line 694 of file purepursuit_planner.cpp.
std::string purepursuit_planner_node::position_source_ [private] |
Mode for reading the position of the robot ("ODOM", "MAP")
Definition at line 710 of file purepursuit_planner.cpp.
Definition at line 680 of file purepursuit_planner.cpp.
queue<Path> purepursuit_planner_node::qPath [private] |
Vector with next paths to follow.
Definition at line 692 of file purepursuit_planner.cpp.
Service to enable/disable back laser.
Definition at line 751 of file purepursuit_planner.cpp.
Service to enable/disable front laser.
Definition at line 749 of file purepursuit_planner.cpp.
ROS Publishes the status of the robot
Definition at line 716 of file purepursuit_planner.cpp.
publish the transformation between map->base_link
Definition at line 721 of file purepursuit_planner.cpp.
Definition at line 744 of file purepursuit_planner.cpp.
unsigned int purepursuit_planner_node::ui_position_source [private] |
Mode in numeric format.
Definition at line 712 of file purepursuit_planner.cpp.
General status diagnostic updater.
Definition at line 732 of file purepursuit_planner.cpp.
Diagnostic to control the frequency of the published odom.
Definition at line 730 of file purepursuit_planner.cpp.
Publish to cmd vel (Ackermann) It will publish into command velocity (for the robot)
Definition at line 719 of file purepursuit_planner.cpp.