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 _traj_executor_CPP_
00028 #define _traj_executor_CPP_
00029
00038
00039 #include <ros/ros.h>
00040 #include <trajectory_planner/c_trajectory.h>
00041 #include <trajectory_planner/c_manage_trajectory.h>
00042 #include <atlasmv_base/AtlasmvStatus.h>
00043 #include <atlasmv_base/AtlasmvMotionCommand.h>
00044 #include <pcl/ros/conversions.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/point_types.h>
00047 #include <math.h>
00048 #include <boost/lexical_cast.hpp>
00049 #include <boost/format.hpp>
00050 #include <trajectory_planner/traj_info.h>
00051
00052
00053 ros::Publisher commandPublisher;
00054 trajectory_planner::traj_info info;
00055 atlasmv_base::AtlasmvMotionCommand command;
00056 ros::NodeHandle* p_n;
00057 double dist_init;
00058 atlasmv_base::AtlasmvStatus base_status;
00059
00060
00067 void send_command_message(int current_node)
00068 {
00069 if(current_node != -1 && static_cast<int>(info.alpha.size())>current_node)
00070 {
00071 command.dir=info.alpha[current_node];
00072 command.speed= info.speed[current_node];
00073 command.lifetime=INFINITY;
00074 command.priority=2;
00075 std::cout<<"DIR -> "<<command.dir<<std::endl;
00076 std::cout<<"SPEED -> "<<command.speed<<std::endl;
00077 }
00078 else
00079 {
00080 command.dir=0.0;
00081 command.speed=0.0;
00082 command.lifetime=INFINITY;
00083 command.priority=2;
00084 }
00085 command.header.stamp=ros::Time::now();
00086 commandPublisher.publish(command);
00087 struct timeval tv;
00088 struct timezone tz;
00089 struct tm *tm;
00090 gettimeofday(&tv, &tz);
00091 tm=localtime(&tv.tv_sec);
00092 printf("Tempooexec %d:%02d:%02d %d \n", tm->tm_hour, tm->tm_min,
00093 tm->tm_sec, tv.tv_usec);
00094 }
00095
00096
00104 bool jump_node(double dist_init,int node)
00105 {
00106 if(node!=-1 && static_cast<int>(info.arc.size())>node)
00107 {
00108 if(info.arc[node]>0)
00109 {
00110 if(info.total_arc[node] <= (base_status.distance_traveled-dist_init))
00111 {
00112 return true;
00113 }
00114 }
00115 else
00116 {
00117 if(info.total_arc[node] >= (base_status.distance_traveled-dist_init))
00118 {
00119 return true;
00120 }
00121 }
00122 }
00123 return false;
00124 }
00125
00126
00132 void StatusMessageHandler(const atlasmv_base::AtlasmvStatus& msg)
00133 {
00134 base_status=msg;
00135 }
00136
00137
00143 void Info_handler(const trajectory_planner::traj_info& msg)
00144 {
00145 info=msg;
00146 dist_init= base_status.distance_traveled;
00147
00148 }
00149
00150
00158 int main(int argc, char **argv)
00159 {
00160 ros::init(argc, argv, "trajectory_executor_nodelet");
00161 ros::NodeHandle n("~");
00162 p_n=&n;
00163
00164
00165 ros::Subscriber subscribe_traj_info = n.subscribe ("/trajectory_information", 1, Info_handler);
00166 ros::Subscriber subscribeStatusMessages = n.subscribe ("/atlasmv/base/status", 1, StatusMessageHandler);
00167 ros::Rate loop_rate(10);
00168
00169
00170 commandPublisher = n.advertise<atlasmv_base::AtlasmvMotionCommand>("/atlasmv/base/motion", 1);
00171 int node=0;
00172
00173 while(ros::ok())
00174 {
00175 loop_rate.sleep();
00176 ros::spinOnce();
00177
00178 if(info.arc.size()==0)
00179 continue;
00180
00181
00182
00183
00184
00185
00186 bool jump_to_next_node = jump_node(dist_init,node);
00187 if(jump_to_next_node)
00188 {
00189 if(node==static_cast<int>((info.arc.size()-1)))
00190 {
00191 node=-1;
00192 }
00193 else
00194 {
00195 node++;
00196 }
00197 }
00198
00199
00200 send_command_message(node);
00201
00202 }
00203 }
00204 #endif