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 HUMAN_PROC_H
00028 #define HUMAN_PROC_H
00029
00030 #include <ros/ros.h>
00031 #include <nav_msgs/Odometry.h>
00032 #include <nav_msgs/Path.h>
00033
00034 #include <move_base_msgs/MoveBaseAction.h>
00035 #include <actionlib/client/simple_action_client.h>
00036 #include <tf/transform_datatypes.h>
00037 #include <tf/transform_broadcaster.h>
00038 #include <tf/transform_listener.h>
00039
00040 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00041
00042 #include <ar_pose/ARMarkers.h>
00043 #include <ar_pose/ARMarker.h>
00044
00045 #include "std_msgs/String.h"
00046
00047 #include "humanPoses.h"
00048
00049 #include "TrajectoryObservation.h"
00050
00051 geometry_msgs::PoseStamped leader_pose;
00052 geometry_msgs::PoseStamped leader_goal[4];
00053 geometry_msgs::PoseStamped robot_goal;
00054 geometry_msgs::PoseStamped next_pose;
00055 geometry_msgs::PoseWithCovarianceStamped robot_pose;
00056 move_base_msgs::MoveBaseGoal goal;
00057 nav_msgs::Path leader_path;
00058 geometry_msgs::Twist cmd_vel;
00059 trajectory_simulator::TrajectoryObservation candidate_;
00060
00061 tf::TransformListener* listener = NULL;
00062 tf::StampedTransform transform;
00063 geometry_msgs::PoseStamped source_pose;
00064 geometry_msgs::PoseStamped target_pose;
00065
00066 ros::Subscriber pose_subscriber;
00067 ros::Subscriber ar_pose_sub;
00068 ros::Subscriber dyn_objects_subscriber;
00069 ros::Subscriber leader_goal_subscriber;
00070 ros::Subscriber robot_goal_subscriber;
00071 ros::Subscriber robot_pose_subscriber;
00072
00073 ros::Publisher pathPublisher;
00074 ros::Publisher robot_cmd_vel;
00075 ros::Publisher next_posePublisher;
00076
00077 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00078
00079 int num_markers;
00080 int marker_id, marker_type;
00081 uint leader_id = 99;
00082 double goals_distance = 99;
00083 double robot2goal_distance, leader2goal_distance;
00084 bool path_initialized = false;
00085 bool send_goal = true;
00086 bool start_to_follow = false;
00087 bool leader_found = false;
00088 double dist, theta, theta_max = M_PI, dmax = 15.0, dmin = 1.5;
00089 double d , tnow, tlast;
00090
00091 void target_pose_callback(const nav_msgs::Odometry::ConstPtr& msg);
00092 void ar_pose_callback(const ar_pose::ARMarkers::ConstPtr& markers);
00093 void dyn_objects_callback(const trajectory_simulator::TrajectoryObservation::ConstPtr & dyn_objects);
00094 void leader_goal_callback(const geometry_msgs::PoseStamped::ConstPtr & msg);
00095 void robot_goal_callback(const geometry_msgs::PoseStamped::ConstPtr & msg);
00096 void robot_pose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & msg);
00097
00098 double euclidean_dist(double x1,double y1,double x2, double y2){
00099 double dist2 = ((x1-x2)*(x1-x2))+((y1-y2)*(y1-y2));
00100 return (sqrt(dist2));
00101 }
00102
00103
00104 #endif // HUMAN_PROC_H
00105