00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef _trajectory_planner_nodelet_H_
00028 #define _trajectory_planner_nodelet_H_
00029
00030 #include <ros/ros.h>
00031 #include <trajectory_planner/c_trajectory.h>
00032 #include <trajectory_planner/c_manage_trajectory.h>
00033 #include <atlasmv_base/AtlasmvStatus.h>
00034 #include <atlasmv_base/AtlasmvMotionCommand.h>
00035 #include <pcl/ros/conversions.h>
00036 #include <pcl/point_cloud.h>
00037 #include <pcl/point_types.h>
00038 #include <mtt/TargetListPC.h>
00039 #include <math.h>
00040 #include <boost/lexical_cast.hpp>
00041 #include <boost/format.hpp>
00042 #include "define_trajectories.h"
00043 #include <tf/transform_broadcaster.h>
00044 #include <tf/transform_listener.h>
00045 #include <trajectory_planner/coordinates.h>
00046 #include <geometry_msgs/Pose.h>
00047
00048
00049 #define PFLN printf("FILE %s LINE %d\n",__FILE__, __LINE__);
00050 #define _D_ 0.50
00051 #define _NUM_TRAJ_ 20
00052 #define _NUM_NODES_ 9
00053
00054 #define _VEHICLE_HEIGHT_TOP_ 0.66
00055 #define _VEHICLE_HEIGHT_BOTTOM_ 0.055
00056 #define _VEHICLE_LENGHT_FRONT_ 0.62
00057 #define _VEHICLE_LENGHT_BACK_ 0.2
00058 #define _VEHICLE_WIDTH_ 0.42
00059
00060
00061 using namespace visualization_msgs;
00062
00063 #ifdef _trajectory_planner_nodelet_CPP_
00064 #define _EXTERN_
00065 #else
00066 #define _EXTERN_ extern
00067 #endif
00068
00069
00070
00071
00072
00073
00074 void StatusMessageHandler(const atlasmv_base::AtlasmvStatus& msg);
00075 int main(int argc, char **argv);
00076 vector<double> set_speed_vector(c_trajectoryPtr t);
00077 bool jump_node(double dist_init,int node, c_trajectoryPtr t);
00078 void send_command_message(vector<double> speed_setted,int current_node, c_trajectoryPtr t);
00079
00080
00081 _EXTERN_ ros::NodeHandle* p_n;
00082 _EXTERN_ tf::TransformListener *p_listener;
00083 _EXTERN_ tf::StampedTransform transformw;
00084 _EXTERN_ tf::StampedTransform transform_mtt;
00085 _EXTERN_ ros::Publisher commandPublisher;
00086 _EXTERN_ c_manage_trajectoryPtr manage_vt;
00087
00088 #endif