trajectory_planner_nodelet.h
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 #ifndef _trajectory_planner_nodelet_H_
28 #define _trajectory_planner_nodelet_H_
29 
30 #include <ros/ros.h>
33 #include <atlasmv_base/AtlasmvStatus.h>
34 #include <atlasmv_base/AtlasmvMotionCommand.h>
35 #include <pcl/conversions.h>
36 #include <pcl/point_cloud.h>
37 #include <pcl/point_types.h>
38 #include <mtt/TargetListPC.h>
39 #include <math.h>
40 #include <boost/lexical_cast.hpp>
41 #include <boost/format.hpp>
42 #include "define_trajectories.h"
43 #include <tf/transform_broadcaster.h>
44 #include <tf/transform_listener.h>
45 #include <trajectory_planner/coordinates.h>
46 #include <geometry_msgs/Pose.h>
47 
48 // Defines
49 #define PFLN printf("FILE %s LINE %d\n",__FILE__, __LINE__);
50 #define _D_ 0.50
51 #define _NUM_TRAJ_ 20
52 #define _NUM_NODES_ 9
53 
54 #define _VEHICLE_HEIGHT_TOP_ 0.66
55 #define _VEHICLE_HEIGHT_BOTTOM_ 0.055
56 #define _VEHICLE_LENGHT_FRONT_ 0.62
57 #define _VEHICLE_LENGHT_BACK_ 0.2
58 #define _VEHICLE_WIDTH_ 0.42
59 
60 //namepaces
61 using namespace visualization_msgs;
62 
63 #ifdef _trajectory_planner_nodelet_CPP_
64 #define _EXTERN_
65 #else
66 #define _EXTERN_ extern
67 #endif
68 
69 // ___________________________________
70 // | |
71 // | PROTOTYPES |
72 // |_________________________________|
73 // Defined in trajectory_planner_nodelet.cpp
74 void StatusMessageHandler(const atlasmv_base::AtlasmvStatus& msg);
75 int main(int argc, char **argv);
76 vector<double> set_speed_vector(c_trajectoryPtr t);
77 bool jump_node(double dist_init,int node, c_trajectoryPtr t);
78 void send_command_message(vector<double> speed_setted,int current_node, c_trajectoryPtr t);
79 
80 // Global Vars
81 _EXTERN_ ros::NodeHandle* p_n;
82 _EXTERN_ tf::TransformListener *p_listener;
83 _EXTERN_ tf::StampedTransform transformw;
84 _EXTERN_ tf::StampedTransform transform_mtt;
85 _EXTERN_ ros::Publisher commandPublisher;
87 
88 #endif
_EXTERN_ ros::NodeHandle * p_n
void send_command_message(vector< double > speed_setted, int current_node, c_trajectoryPtr t)
boost::shared_ptr< c_trajectory > c_trajectoryPtr
Definition: c_trajectory.h:150
class which evaluates the trajectories planned
_EXTERN_ c_manage_trajectoryPtr manage_vt
_EXTERN_ tf::TransformListener * p_listener
class which generates a few number of trajectories from an input file
double dist_init
_EXTERN_ tf::StampedTransform transformw
boost::shared_ptr< c_manage_trajectory > c_manage_trajectoryPtr
_EXTERN_ ros::Publisher commandPublisher
vector< double > set_speed_vector(c_trajectoryPtr t)
Determine the speed vector.
void StatusMessageHandler(const atlasmv_base::AtlasmvStatus &msg)
Define message status.
bool jump_node(double dist_init, int node, c_trajectoryPtr t)
_EXTERN_ tf::StampedTransform transform_mtt
int main(int argc, char **argv)
Generates a frame higher than the car frame, to publish the point cloud to the mtt.
#define _EXTERN_


trajectory_planner
Author(s): Joel Pereira
autogenerated on Mon Mar 2 2015 01:32:54