Defines | Functions | Variables

/home/joel/ros_workspace/lar3/planning/trajectory_planner/src/trajectory_planner_nodelet.h File Reference

#include <ros/ros.h>
#include <trajectory_planner/c_trajectory.h>
#include <trajectory_planner/c_manage_trajectory.h>
#include <atlasmv_base/AtlasmvStatus.h>
#include <atlasmv_base/AtlasmvMotionCommand.h>
#include <pcl/ros/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <mtt/TargetList.h>
#include <math.h>
#include <boost/lexical_cast.hpp>
#include <boost/format.hpp>
#include "define_trajectories.h"
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <trajectory_planner/coordinates.h>
#include <geometry_msgs/Pose.h>
Include dependency graph for trajectory_planner_nodelet.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Defines

#define _D_   0.50
#define _EXTERN_   extern
#define _NUM_NODES_   9
#define _NUM_TRAJ_   5
#define _VEHICLE_HEIGHT_BOTTOM_   0.055
#define _VEHICLE_HEIGHT_TOP_   0.66
#define _VEHICLE_LENGHT_BACK_   0.2
#define _VEHICLE_LENGHT_FRONT_   0.62
#define _VEHICLE_WIDTH_   0.42
#define PFLN   printf("FILE %s LINE %d\n",__FILE__, __LINE__);

Functions

bool jump_node (double dist_init, int node, c_trajectoryPtr t)
int main (int argc, char **argv)
 Generates a frame higher than the car frame, to publish the point cloud to the mtt.
void send_command_message (vector< double > speed_setted, int current_node, c_trajectoryPtr t)
vector< double > set_speed_vector (c_trajectoryPtr t)
 Determine the speed vector.
void StatusMessageHandler (const atlasmv_base::AtlasmvStatus &msg)
 Define message status.

Variables

_EXTERN_ ros::Publisher commandPublisher
_EXTERN_ c_manage_trajectoryPtr manage_vt
_EXTERN_ tf::TransformListener * p_listener
_EXTERN_ ros::NodeHandle * p_n
_EXTERN_ tf::StampedTransform transform_mtt
_EXTERN_ tf::StampedTransform transformw

Define Documentation

#define _D_   0.50

Definition at line 24 of file trajectory_planner_nodelet.h.

#define _EXTERN_   extern

Definition at line 40 of file trajectory_planner_nodelet.h.

#define _NUM_NODES_   9

Definition at line 26 of file trajectory_planner_nodelet.h.

#define _NUM_TRAJ_   5

Definition at line 25 of file trajectory_planner_nodelet.h.

#define _VEHICLE_HEIGHT_BOTTOM_   0.055

Definition at line 29 of file trajectory_planner_nodelet.h.

#define _VEHICLE_HEIGHT_TOP_   0.66

Definition at line 28 of file trajectory_planner_nodelet.h.

#define _VEHICLE_LENGHT_BACK_   0.2

Definition at line 31 of file trajectory_planner_nodelet.h.

#define _VEHICLE_LENGHT_FRONT_   0.62

Definition at line 30 of file trajectory_planner_nodelet.h.

#define _VEHICLE_WIDTH_   0.42

Definition at line 32 of file trajectory_planner_nodelet.h.

#define PFLN   printf("FILE %s LINE %d\n",__FILE__, __LINE__);

Definition at line 23 of file trajectory_planner_nodelet.h.


Function Documentation

bool jump_node ( double  dist_init,
int  node,
c_trajectoryPtr  t 
)
int main ( int  argc,
char **  argv 
)

Generates a frame higher than the car frame, to publish the point cloud to the mtt.

Returns:
Parameters:
int
char**
Returns:
int

Generates a frame higher than the car frame, to publish the point cloud to the mtt.

Publishes the trajectories message and the command message

Parameters:
intargc
char**argv
Returns:
int

Definition at line 124 of file APgenerator.cpp.

void send_command_message ( vector< double >  speed_setted,
int  current_node,
c_trajectoryPtr  t 
)
vector<double> set_speed_vector ( boost::shared_ptr< c_trajectory t)

Determine the speed vector.

Parameters:
c_trajectoryPtrt
Returns:
vector<double>

Definition at line 73 of file trajectory_planner_nodelet.cpp.

void StatusMessageHandler ( const atlasmv_base::AtlasmvStatus &  msg)

Define message status.

Parameters:
constatlasmv_base::AtlasmvStatus& msg
Returns:
void

Definition at line 106 of file trajectory_executive.cpp.


Variable Documentation

_EXTERN_ ros::Publisher commandPublisher

Definition at line 59 of file trajectory_planner_nodelet.h.

Definition at line 60 of file trajectory_planner_nodelet.h.

_EXTERN_ tf::TransformListener* p_listener

Definition at line 56 of file trajectory_planner_nodelet.h.

_EXTERN_ ros::NodeHandle* p_n

Definition at line 55 of file trajectory_planner_nodelet.h.

_EXTERN_ tf::StampedTransform transform_mtt

Definition at line 58 of file trajectory_planner_nodelet.h.

_EXTERN_ tf::StampedTransform transformw

Definition at line 57 of file trajectory_planner_nodelet.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


trajectory_planner
Author(s): joel
autogenerated on Thu Jul 26 2012 21:36:28