Convenience functions for motion control.
More...
#include <trgen.h>
#include "robodata.h"
#include <robot.h>
#include <movehelper.h>
#include <path_simplifier.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <math.h>
#include <map.h>
#include <robomath.h>
#include <mcl_robot.h>
#include <string.h>
#include <ul_log.h>
Functions |
| | UL_LOG_CUST (ulogd_movehelper) |
| void | robot_trajectory_new (struct TrajectoryConstraints *tc) |
| | Initializes new trajectory object for adding points.
|
| void | robot_trajectory_new_backward (struct TrajectoryConstraints *tc) |
| void | robot_set_est_pos_notrans (double x, double y, double phi) |
| | Sets actual position of the robot and with respoect to color of the team.
|
| void | robot_trajectory_add_point_notrans (double x_m, double y_m) |
| | Adds point in absolute coordinates to previously initialized trajectory object.
|
| bool | get_arrive_from_point (double target_x_m, double target_y_m, struct move_target_heading heading, double *point_x_m, double *point_y_m) |
| void | robot_trajectory_add_final_point_notrans (double x_m, double y_m, struct move_target_heading heading) |
| | Adds final point to trajectory objects and starts robot movement.
|
| void | robot_stop () |
| | Stops actual movement.
|
| void | robot_send_speed (double left, double right) |
| void | robot_goto_notrans (double x, double y, struct move_target_heading heading, struct TrajectoryConstraints *tc) |
| | Makes move the robot to a target position.
|
| void | robot_moveto_notrans (double x, double y, struct move_target_heading heading, struct TrajectoryConstraints *tc) |
| | Move to a point using straight line trajectory.
|
| void | robot_move_by (double distance, struct move_target_heading heading, struct TrajectoryConstraints *tc) |
| | Move robot forward or backward.
|
Variables |
| struct TrajectoryConstraints | trajectoryConstraintsDefault |
| bool | init_ekf_flag = false |
Detailed Description
Convenience functions for motion control.
- Author:
- Michal Sojka
- Date:
- Wed Jun 13 13:27:58 2007
Function Documentation
| bool get_arrive_from_point |
( |
double |
target_x_m, |
|
|
double |
target_y_m, |
|
|
struct move_target_heading |
heading, |
|
|
double * |
point_x_m, |
|
|
double * |
point_y_m | |
|
) |
| | |
Makes move the robot to a target position.
Go to a point using path planning to avoid apriori known obstacles.
Use path panner to find the trajectory. This function is intended to be called from main FSM.
- Parameters:
-
| x | X coordinate in meters. |
| y | Y coordinate in meters. |
| heading | Desired heading of the robot at goal point. |
Move robot forward or backward.
- Parameters:
-
| distance | Distance in meters ( >0 forward, <0 backward) |
| heading | Final heading |
| tc | Trajectory constrains |
Move to a point using straight line trajectory.
If ARIVE_FROM is set, then the trajectory will be composed two lines.... TODO
| void robot_send_speed |
( |
double |
left, |
|
|
double |
right | |
|
) |
| | |
| void robot_set_est_pos_notrans |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
phi | |
|
) |
| | |
Sets actual position of the robot and with respoect to color of the team.
Should be used for setting initial position of the robot.
Stops actual movement.
Stop robot immediately.
| void robot_trajectory_add_final_point_notrans |
( |
double |
x_m, |
|
|
double |
y_m, |
|
|
struct move_target_heading |
heading | |
|
) |
| | |
Adds final point to trajectory objects and starts robot movement.
- Parameters:
-
| x_m | X coordinate in meters. |
| y_m | Y coordinate in meters. |
| heading | Desired heading (in degrees) of the robot in this point. NAN means don't care. Positive number or zero means turn counter-clockwise, negative number means turn clockwise. Example: DEG2RAD(90) means turn up counter-clockwise and DEG2RAD(-270) means turn up clockwise. |
| void robot_trajectory_add_point_notrans |
( |
double |
x_m, |
|
|
double |
y_m | |
|
) |
| | |
Adds point in absolute coordinates to previously initialized trajectory object.
- Parameters:
-
| x_m | X coordinate in meters. |
| y_m | Y coordinate in meters. |
Initializes new trajectory object for adding points.
Path planner will not be used.
- Parameters:
-
| tc | Constrains for the trajectory. |
| UL_LOG_CUST |
( |
ulogd_movehelper |
|
) |
|
Variable Documentation
Initial value: {
maxv: 1,
maxomega: 1,
maxangacc: 1,
maxacc: 1,
maxcenacc: 1,
maxe: (double)ROBOT_WIDTH_MM/2.0/1000.0
}