leader_follower.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 HUMAN_PROC_H
28 #define HUMAN_PROC_H
29 
30 #include <ros/ros.h>
31 #include <nav_msgs/Odometry.h>
32 #include <nav_msgs/Path.h>
33 
34 #include <move_base_msgs/MoveBaseAction.h>
35 #include <actionlib/client/simple_action_client.h>
36 #include <tf/transform_datatypes.h>
37 #include <tf/transform_broadcaster.h>
38 #include <tf/transform_listener.h>
39 
40 #include <geometry_msgs/PoseWithCovarianceStamped.h>
41 
42 #include <ar_pose/ARMarkers.h>
43 #include <ar_pose/ARMarker.h>
44 
45 #include "std_msgs/String.h"
46 // #include "humanPose.h" //this is for the msg defined
47 #include "humanPoses.h"
48 
49 #include "TrajectoryObservation.h"
50 
51 geometry_msgs::PoseStamped leader_pose;
52 geometry_msgs::PoseStamped leader_goal[4];
53 geometry_msgs::PoseStamped robot_goal;
54 geometry_msgs::PoseStamped next_pose;
55 geometry_msgs::PoseWithCovarianceStamped robot_pose;
56 move_base_msgs::MoveBaseGoal goal;
57 nav_msgs::Path leader_path;
58 geometry_msgs::Twist cmd_vel;
60 
61 tf::TransformListener* listener = NULL;
62 tf::StampedTransform transform;
63 geometry_msgs::PoseStamped source_pose;
64 geometry_msgs::PoseStamped target_pose;
65 
66 ros::Subscriber pose_subscriber;
67 ros::Subscriber ar_pose_sub;
68 ros::Subscriber dyn_objects_subscriber;
69 ros::Subscriber leader_goal_subscriber;
70 ros::Subscriber robot_goal_subscriber;
71 ros::Subscriber robot_pose_subscriber;
72 
73 ros::Publisher pathPublisher;
74 ros::Publisher robot_cmd_vel;
75 ros::Publisher next_posePublisher;
76 
77 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
78 
81 uint leader_id = 99; //must be different from any id at initialization
82 double goals_distance = 99;
84 bool path_initialized = false;
85 bool send_goal = true;
86 bool start_to_follow = false;
87 bool leader_found = false;
88 double dist, theta, theta_max = M_PI, dmax = 15.0, dmin = 1.5;
89 double d , tnow, tlast;
90 
91 void target_pose_callback(const nav_msgs::Odometry::ConstPtr& msg);
92 void ar_pose_callback(const ar_pose::ARMarkers::ConstPtr& markers);
94 void leader_goal_callback(const geometry_msgs::PoseStamped::ConstPtr & msg);
95 void robot_goal_callback(const geometry_msgs::PoseStamped::ConstPtr & msg);
96 void robot_pose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & msg);
97 
98 double euclidean_dist(double x1,double y1,double x2, double y2){
99  double dist2 = ((x1-x2)*(x1-x2))+((y1-y2)*(y1-y2));
100  return (sqrt(dist2));
101 }
102 
103 
104 #endif // HUMAN_PROC_H
105 
geometry_msgs::PoseStamped next_pose
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
ros::Subscriber pose_subscriber
geometry_msgs::PoseStamped robot_goal
void target_pose_callback(const nav_msgs::Odometry::ConstPtr &msg)
tf::StampedTransform transform
move_base_msgs::MoveBaseGoal goal
void robot_pose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
void ar_pose_callback(const ar_pose::ARMarkers::ConstPtr &markers)
void dyn_objects_callback(const trajectory_simulator::TrajectoryObservation::ConstPtr &dyn_objects)
uint leader_id
double theta_max
geometry_msgs::PoseStamped source_pose
bool leader_found
geometry_msgs::PoseWithCovarianceStamped robot_pose
ros::Subscriber dyn_objects_subscriber
geometry_msgs::Twist cmd_vel
double dist
nav_msgs::Path leader_path
ros::Subscriber robot_goal_subscriber
ros::Subscriber leader_goal_subscriber
double theta
double tnow
double dmax
double euclidean_dist(double x1, double y1, double x2, double y2)
double leader2goal_distance
ros::Subscriber ar_pose_sub
tf::TransformListener * listener
geometry_msgs::PoseStamped leader_pose
double d
int num_markers
ros::Publisher robot_cmd_vel
boost::shared_ptr< ::trajectory_simulator::TrajectoryObservation_< ContainerAllocator > const > ConstPtr
double robot2goal_distance
geometry_msgs::PoseStamped leader_goal[4]
int marker_id
void leader_goal_callback(const geometry_msgs::PoseStamped::ConstPtr &msg)
ros::Subscriber robot_pose_subscriber
int marker_type
double dmin
trajectory_simulator::TrajectoryObservation candidate_
ros::Publisher pathPublisher
bool send_goal
geometry_msgs::PoseStamped target_pose
bool start_to_follow
ros::Publisher next_posePublisher
void robot_goal_callback(const geometry_msgs::PoseStamped::ConstPtr &msg)
double goals_distance
bool path_initialized
double tlast


leader_follower
Author(s): Procopio Silveira Stein
autogenerated on Mon Mar 2 2015 01:32:08