git commit -m "first commit"
This commit is contained in:
210
navigations/follow_waypoints/CMakeLists.txt
Executable file
210
navigations/follow_waypoints/CMakeLists.txt
Executable file
@@ -0,0 +1,210 @@
|
||||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(follow_waypoints)
|
||||
|
||||
## Compile as C++11, supported in ROS Kinetic and newer
|
||||
# add_compile_options(-std=c++11)
|
||||
|
||||
## Find catkin macros and libraries
|
||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||
## is used, also find other catkin packages
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
actionlib
|
||||
dynamic_reconfigure
|
||||
geometry_msgs
|
||||
move_base_msgs
|
||||
roscpp
|
||||
std_msgs
|
||||
tf
|
||||
)
|
||||
|
||||
## System dependencies are found with CMake's conventions
|
||||
# find_package(Boost REQUIRED COMPONENTS system)
|
||||
|
||||
|
||||
## Uncomment this if the package has a setup.py. This macro ensures
|
||||
## modules and global scripts declared therein get installed
|
||||
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
|
||||
# catkin_python_setup()
|
||||
|
||||
################################################
|
||||
## Declare ROS messages, services and actions ##
|
||||
################################################
|
||||
|
||||
## To declare and build messages, services or actions from within this
|
||||
## package, follow these steps:
|
||||
## * Let MSG_DEP_SET be the set of packages whose message types you use in
|
||||
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
|
||||
## * In the file package.xml:
|
||||
## * add a build_depend tag for "message_generation"
|
||||
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
|
||||
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
|
||||
## but can be declared for certainty nonetheless:
|
||||
## * add a exec_depend tag for "message_runtime"
|
||||
## * In this file (CMakeLists.txt):
|
||||
## * add "message_generation" and every package in MSG_DEP_SET to
|
||||
## find_package(catkin REQUIRED COMPONENTS ...)
|
||||
## * add "message_runtime" and every package in MSG_DEP_SET to
|
||||
## catkin_package(CATKIN_DEPENDS ...)
|
||||
## * uncomment the add_*_files sections below as needed
|
||||
## and list every .msg/.srv/.action file to be processed
|
||||
## * uncomment the generate_messages entry below
|
||||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
|
||||
|
||||
## Generate messages in the 'msg' folder
|
||||
# add_message_files(
|
||||
# FILES
|
||||
# Message1.msg
|
||||
# Message2.msg
|
||||
# )
|
||||
|
||||
## Generate services in the 'srv' folder
|
||||
# add_service_files(
|
||||
# FILES
|
||||
# Service1.srv
|
||||
# Service2.srv
|
||||
# )
|
||||
|
||||
## Generate actions in the 'action' folder
|
||||
# add_action_files(
|
||||
# FILES
|
||||
# Action1.action
|
||||
# Action2.action
|
||||
# )
|
||||
|
||||
## Generate added messages and services with any dependencies listed here
|
||||
# generate_messages(DEPENDENCIES geometry_msgs)
|
||||
|
||||
################################################
|
||||
## Declare ROS dynamic reconfigure parameters ##
|
||||
################################################
|
||||
|
||||
## To declare and build dynamic reconfigure parameters within this
|
||||
## package, follow these steps:
|
||||
## * In the file package.xml:
|
||||
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
|
||||
## * In this file (CMakeLists.txt):
|
||||
## * add "dynamic_reconfigure" to
|
||||
## find_package(catkin REQUIRED COMPONENTS ...)
|
||||
## * uncomment the "generate_dynamic_reconfigure_options" section below
|
||||
## and list every .cfg file to be processed
|
||||
|
||||
## Generate dynamic reconfigure parameters in the 'cfg' folder
|
||||
generate_dynamic_reconfigure_options(
|
||||
cfg/FollowWayPoints.cfg
|
||||
)
|
||||
|
||||
###################################
|
||||
## catkin specific configuration ##
|
||||
###################################
|
||||
## The catkin_package macro generates cmake config files for your package
|
||||
## Declare things to be passed to dependent projects
|
||||
## INCLUDE_DIRS: uncomment this if your package contains header files
|
||||
## LIBRARIES: libraries you create in this project that dependent projects also need
|
||||
## CATKIN_DEPENDS: catkin_packages dependent projects also need
|
||||
## DEPENDS: system dependencies of this project that dependent projects also need
|
||||
catkin_package(
|
||||
INCLUDE_DIRS include
|
||||
LIBRARIES ${PROJECT_NAME}
|
||||
CATKIN_DEPENDS actionlib geometry_msgs move_base_msgs roscpp std_msgs message_runtime
|
||||
# DEPENDS system_lib
|
||||
)
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
## Specify additional locations of header files
|
||||
## Your package locations should be listed before other locations
|
||||
include_directories(
|
||||
include
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
## Declare a C++ library
|
||||
add_library(${PROJECT_NAME}
|
||||
src/follow_waypoints.cpp
|
||||
)
|
||||
|
||||
## Add cmake target dependencies of the library
|
||||
## as an example, code may need to be generated before libraries
|
||||
## either from message generation or dynamic reconfigure
|
||||
add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
## Declare a C++ executable
|
||||
## With catkin_make all packages are built within a single CMake context
|
||||
## The recommended prefix ensures that target names across packages don't collide
|
||||
add_executable(${PROJECT_NAME}_node src/follow_waypoints_node.cpp)
|
||||
|
||||
## Rename C++ executable without prefix
|
||||
## The above recommended prefix causes long target names, the following renames the
|
||||
## target back to the shorter version for ease of user use
|
||||
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
|
||||
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
|
||||
|
||||
## Add cmake target dependencies of the executable
|
||||
## same as for the library above
|
||||
add_dependencies(${PROJECT_NAME}_node ${PROJECT_NAME}_gencfg ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
## Specify libraries to link a library or executable target against
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}_node
|
||||
${PROJECT_NAME}
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
# all install targets should use catkin DESTINATION variables
|
||||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
|
||||
|
||||
## Mark executable scripts (Python etc.) for installation
|
||||
## in contrast to setup.py, you can choose the destination
|
||||
# catkin_install_python(PROGRAMS
|
||||
# scripts/my_python_script
|
||||
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark executables for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
|
||||
install(TARGETS ${PROJECT_NAME}_node
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
||||
|
||||
## Mark libraries for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
|
||||
install(TARGETS ${PROJECT_NAME}
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
|
||||
)
|
||||
|
||||
## Mark cpp header files for installation
|
||||
install(DIRECTORY launch/
|
||||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}/launch
|
||||
)
|
||||
|
||||
## Mark other files for installation (e.g. launch and bag files, etc.)
|
||||
# install(FILES
|
||||
# # myfile1
|
||||
# # myfile2
|
||||
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
||||
# )
|
||||
|
||||
#############
|
||||
## Testing ##
|
||||
#############
|
||||
|
||||
## Add gtest based cpp test target and link libraries
|
||||
# catkin_add_gtest(${PROJECT_NAME}-test test/test_follow_waypoints.cpp)
|
||||
# if(TARGET ${PROJECT_NAME}-test)
|
||||
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
|
||||
# endif()
|
||||
|
||||
## Add folders to be run by python nosetests
|
||||
# catkin_add_nosetests(test)
|
||||
8
navigations/follow_waypoints/cfg/FollowWayPoints.cfg
Executable file
8
navigations/follow_waypoints/cfg/FollowWayPoints.cfg
Executable file
@@ -0,0 +1,8 @@
|
||||
#!/usr/bin/env python
|
||||
PACKAGE = 'follow_waypoints'
|
||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||
|
||||
gen = ParameterGenerator()
|
||||
gen.add("patrol_mode", bool_t, 0, "Follow the currently given waypoints repeatedly", False)
|
||||
|
||||
exit(gen.generate(PACKAGE, "follow_waypoints", "FollowWayPoints"))
|
||||
69
navigations/follow_waypoints/include/follow_waypoints/follow_waypoints.h
Executable file
69
navigations/follow_waypoints/include/follow_waypoints/follow_waypoints.h
Executable file
@@ -0,0 +1,69 @@
|
||||
#ifndef FOLLOW_WAYPOINTS_H_
|
||||
#define FOLLOW_WAYPOINTS_H_
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <math.h>
|
||||
#include <actionlib/client/simple_action_client.h>
|
||||
#include <actionlib_msgs/GoalID.h>
|
||||
#include <move_base_msgs/MoveBaseAction.h>
|
||||
#include <move_base_msgs/MoveBaseGoal.h>
|
||||
#include <tf/transform_listener.h>
|
||||
#include <std_srvs/Trigger.h>
|
||||
#include <dynamic_reconfigure/server.h>
|
||||
#include <follow_waypoints/FollowWayPointsConfig.h>
|
||||
#include <geometry_msgs/PoseArray.h>
|
||||
#include <geometry_msgs/PointStamped.h>
|
||||
#include <geometry_msgs/PoseWithCovarianceStamped.h>
|
||||
#include <geometry_msgs/Quaternion.h>
|
||||
#include <boost/thread.hpp>
|
||||
|
||||
namespace follow_waypoints
|
||||
{
|
||||
class FollowWayPoints
|
||||
{
|
||||
public:
|
||||
FollowWayPoints(ros::NodeHandlePtr nh, std::string node_name);
|
||||
virtual ~FollowWayPoints();
|
||||
void run();
|
||||
private:
|
||||
void dyn_callback(follow_waypoints::FollowWayPointsConfig &config, int32_t level);
|
||||
bool make_path_ready(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
|
||||
bool do_path_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
|
||||
void point_cb(geometry_msgs::PointStamped point);
|
||||
void pub_waypoints_list();
|
||||
void send_move_base_goal(geometry_msgs::PoseWithCovarianceStamped pose);
|
||||
void run_once();
|
||||
geometry_msgs::PoseWithCovarianceStamped to_pose_with_Cov(geometry_msgs::PointStamped point);
|
||||
geometry_msgs::PoseArray toPoseArray(std::vector<geometry_msgs::PoseWithCovarianceStamped> waypoints);
|
||||
|
||||
std::string frame_id_;
|
||||
std::string odom_frame_id_;
|
||||
std::string base_frame_id_;
|
||||
std::string waypoints_to_follow_topic_;
|
||||
std::string waypoints_list_topic_;
|
||||
double wait_duration_;
|
||||
double distance_tolerance_;
|
||||
bool path_ready_;
|
||||
bool waypoints_are_poses_;
|
||||
|
||||
// TF Initialisation -------------------------------------------------------------------
|
||||
tf::TransformListener tf_;
|
||||
tf::TransformListener listener_;
|
||||
|
||||
ros::NodeHandlePtr private_nh_;
|
||||
ros::ServiceServer path_ready_srv_;
|
||||
ros::ServiceServer path_reset_srv_;
|
||||
ros::Publisher pose_array_publisher_;
|
||||
ros::Subscriber waypoints_sub_;
|
||||
actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>* move_base_client_;
|
||||
std::vector<geometry_msgs::PoseWithCovarianceStamped> waypoints_;
|
||||
dynamic_reconfigure::Server<follow_waypoints::FollowWayPointsConfig> server;
|
||||
dynamic_reconfigure::Server<follow_waypoints::FollowWayPointsConfig>::CallbackType f;
|
||||
follow_waypoints::FollowWayPointsConfig dyn_config_;
|
||||
/* Create Thread */
|
||||
boost::thread lineThread;
|
||||
ros::Rate* loop_rate_;
|
||||
};
|
||||
} //follow_waypoints
|
||||
|
||||
#endif
|
||||
26
navigations/follow_waypoints/launch/follow_waypoints.launch
Executable file
26
navigations/follow_waypoints/launch/follow_waypoints.launch
Executable file
@@ -0,0 +1,26 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<arg name="output" default="screen"/>
|
||||
<arg name="goal_frame_id" default="map"/>
|
||||
<arg name="wait_duration" default="0.0"/>
|
||||
<arg name="waypoint_distance_tolerance" default="2"/>
|
||||
<arg name="waypoints_to_follow_topic" default="/clicked_point"/>
|
||||
<arg name="waypoints_list_topic" default="/waypoints"/>
|
||||
<arg name="waypoints_are_poses" default="false"/>
|
||||
<arg name="patrol_mode" default="false"/>
|
||||
|
||||
<param name="goal_frame_id" value="$(arg goal_frame_id)"/>
|
||||
<param name="wait_duration" value="$(arg wait_duration)"/>
|
||||
<param name="waypoint_distance_tolerance" value="$(arg waypoint_distance_tolerance)"/>
|
||||
<param name="waypoints_to_follow_topic" value="$(arg waypoints_to_follow_topic)"/>
|
||||
<param name="waypoints_list_topic" value="$(arg waypoints_list_topic)"/>
|
||||
<param name="waypoints_are_poses" value="$(arg waypoints_are_poses)" type="bool"/>
|
||||
<param name="patrol_mode" value="$(arg patrol_mode)" type="bool"/>
|
||||
|
||||
<node pkg="follow_waypoints" type="follow_waypoints_node" name="follow_waypoints_node" output="$(arg output)" required="true"/>
|
||||
|
||||
<node name="$(anon dynparam)" pkg="dynamic_reconfigure" type="dynparam" args="set_from_parameters follow_waypoints">
|
||||
<param name="patrol_mode" type="bool" value="$(arg patrol_mode)" />
|
||||
</node>
|
||||
</launch>
|
||||
|
||||
79
navigations/follow_waypoints/package.xml
Executable file
79
navigations/follow_waypoints/package.xml
Executable file
@@ -0,0 +1,79 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>follow_waypoints</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The follow_waypoints package</description>
|
||||
|
||||
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||
<!-- Example: -->
|
||||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
||||
<maintainer email="robotics@todo.todo">robotics</maintainer>
|
||||
|
||||
|
||||
<!-- One license tag required, multiple allowed, one license per tag -->
|
||||
<!-- Commonly used license strings: -->
|
||||
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
|
||||
<license>TODO</license>
|
||||
|
||||
|
||||
<!-- Url tags are optional, but multiple are allowed, one per tag -->
|
||||
<!-- Optional attribute type can be: website, bugtracker, or repository -->
|
||||
<!-- Example: -->
|
||||
<!-- <url type="website">http://wiki.ros.org/follow_waypoints</url> -->
|
||||
|
||||
|
||||
<!-- Author tags are optional, multiple are allowed, one per tag -->
|
||||
<!-- Authors do not have to be maintainers, but could be -->
|
||||
<!-- Example: -->
|
||||
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
|
||||
|
||||
|
||||
<!-- The *depend tags are used to specify dependencies -->
|
||||
<!-- Dependencies can be catkin packages or system dependencies -->
|
||||
<!-- Examples: -->
|
||||
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
|
||||
<!-- <depend>roscpp</depend> -->
|
||||
<!-- Note that this is equivalent to the following: -->
|
||||
<!-- <build_depend>roscpp</build_depend> -->
|
||||
<!-- <exec_depend>roscpp</exec_depend> -->
|
||||
<!-- Use build_depend for packages you need at compile time: -->
|
||||
<build_depend>message_generation</build_depend>
|
||||
<!-- Use build_export_depend for packages you need in order to build against this package: -->
|
||||
<!-- <build_export_depend>message_generation</build_export_depend> -->
|
||||
<!-- Use buildtool_depend for build tool packages: -->
|
||||
<!-- <buildtool_depend>catkin</buildtool_depend> -->
|
||||
<!-- Use exec_depend for packages you need at runtime: -->
|
||||
<exec_depend>message_runtime</exec_depend>
|
||||
<!-- Use test_depend for packages you need only for testing: -->
|
||||
<!-- <test_depend>gtest</test_depend> -->
|
||||
<!-- Use doc_depend for packages you need only for building documentation: -->
|
||||
<!-- <doc_depend>doxygen</doc_depend> -->
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>geometry_msgs</build_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_export_depend>geometry_msgs</build_export_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<build_export_depend>std_msgs</build_export_depend>
|
||||
<exec_depend>geometry_msgs</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
|
||||
<build_depend>actionlib</build_depend>
|
||||
<exec_depend>actionlib</exec_depend>
|
||||
|
||||
<build_depend>dynamic_reconfigure</build_depend>
|
||||
<exec_depend>dynamic_reconfigure</exec_depend>
|
||||
|
||||
<build_depend>move_base_msgs</build_depend>
|
||||
<exec_depend>move_base_msgs</exec_depend>
|
||||
|
||||
<build_depend>tf</build_depend>
|
||||
<exec_depend>tf</exec_depend>
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
<!-- Other tools can request additional information be placed here -->
|
||||
|
||||
</export>
|
||||
</package>
|
||||
285
navigations/follow_waypoints/src/follow_waypoints.cpp
Executable file
285
navigations/follow_waypoints/src/follow_waypoints.cpp
Executable file
@@ -0,0 +1,285 @@
|
||||
#include "follow_waypoints/follow_waypoints.h"
|
||||
|
||||
namespace follow_waypoints
|
||||
{
|
||||
FollowWayPoints::FollowWayPoints(ros::NodeHandlePtr nh, std::string node_name) : private_nh_(nh)
|
||||
{
|
||||
if(private_nh_ == NULL) exit(0);
|
||||
// private_nh_ = ros::NodeHandle("~/"+node_name);
|
||||
// Read parameters off the parameter server --------------------------------------------
|
||||
private_nh_->param("goal_frame_id", frame_id_, std::string("map"));
|
||||
private_nh_->param("odom_frame_id", odom_frame_id_, std::string("odom"));
|
||||
private_nh_->param("base_frame_id", base_frame_id_, std::string("base_footprint"));
|
||||
private_nh_->param("wait_duration", wait_duration_, 0.0);
|
||||
private_nh_->param("waypoint_distance_tolerance", distance_tolerance_, 0.0);
|
||||
private_nh_->param("waypoints_to_follow_topic", waypoints_to_follow_topic_, std::string("/clicked_points"));
|
||||
private_nh_->param("waypoints_list_topic", waypoints_list_topic_, std::string("/waypoints"));
|
||||
|
||||
// listen to points or to poses?
|
||||
private_nh_->param("waypoints_are_poses", waypoints_are_poses_, true);
|
||||
|
||||
// list of waypoints to follow
|
||||
// self.waypoints = collections.deque()
|
||||
|
||||
// Is the path provided by the user ready to follow?
|
||||
path_ready_ = false;
|
||||
|
||||
// Dynamic Reconfigure -----------------------------------------------------------------
|
||||
f = boost::bind(&FollowWayPoints::dyn_callback, this, _1, _2);
|
||||
server.setCallback(f);
|
||||
|
||||
// move_base Action client -------------------------------------------------------------
|
||||
move_base_client_ = new actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>("/move_base", true);
|
||||
ROS_INFO("Connecting to move_base...");
|
||||
if(move_base_client_ != NULL) move_base_client_->waitForServer();
|
||||
ROS_INFO("Connected to move_base.");
|
||||
|
||||
// Subscribers & Publishers & Services initialisation ----------------------------------
|
||||
path_ready_srv_ = private_nh_->advertiseService("/path_ready",&FollowWayPoints::make_path_ready, this);
|
||||
path_reset_srv_ = private_nh_->advertiseService("/path_reset",&FollowWayPoints::do_path_reset, this);
|
||||
ROS_INFO("Ready to add two ints.");
|
||||
|
||||
// publish waypoints as pose array - visualise them in rviz
|
||||
pose_array_publisher_ = private_nh_->advertise<geometry_msgs::PoseArray>(waypoints_list_topic_,1, true);
|
||||
|
||||
// Listen to the goal locations
|
||||
waypoints_sub_ = private_nh_->subscribe(waypoints_to_follow_topic_, 1000, &FollowWayPoints::point_cb, this);
|
||||
loop_rate_ = new ros::Rate(20);
|
||||
// // Create thread
|
||||
// lineThread = boost::thread(&FollowWayPoints::run, this);
|
||||
// if(lineThread.joinable()) {
|
||||
// lineThread.join();
|
||||
// }
|
||||
}
|
||||
|
||||
FollowWayPoints::~FollowWayPoints()
|
||||
{
|
||||
delete(move_base_client_);
|
||||
|
||||
}
|
||||
|
||||
void FollowWayPoints::dyn_callback(follow_waypoints::FollowWayPointsConfig &config, int32_t level)
|
||||
{
|
||||
dyn_config_ = config;
|
||||
ROS_INFO("Reconfigure Request: %d", config.patrol_mode);
|
||||
}
|
||||
|
||||
bool FollowWayPoints::make_path_ready(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
|
||||
{
|
||||
path_ready_ = true;
|
||||
res.success = path_ready_;
|
||||
res.message = "path_ready_ = true";
|
||||
return true;
|
||||
}
|
||||
|
||||
bool FollowWayPoints::do_path_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
|
||||
{
|
||||
ROS_WARN("Issuing cancel command to move_base");
|
||||
|
||||
ros::Publisher pub = private_nh_->advertise<actionlib_msgs::GoalID>("/move_base/cancel", 1);
|
||||
pub.publish(actionlib_msgs::GoalID());
|
||||
ROS_WARN("move_base goal cancelled.");
|
||||
|
||||
if(!waypoints_.empty())
|
||||
{
|
||||
waypoints_.clear();
|
||||
pub_waypoints_list();
|
||||
}
|
||||
res.success = path_ready_;
|
||||
res.message = "move_base goal cancelled.";
|
||||
return true;
|
||||
}
|
||||
|
||||
void FollowWayPoints::pub_waypoints_list()
|
||||
{
|
||||
pose_array_publisher_.publish(toPoseArray(waypoints_));
|
||||
}
|
||||
|
||||
void FollowWayPoints::point_cb(geometry_msgs::PointStamped point)
|
||||
{
|
||||
waypoints_.insert(waypoints_.end(), this->to_pose_with_Cov(point));
|
||||
ROS_INFO("Added new waypoint -> (%f, %f) | # Waypoints: %d", point.point.x, point.point.y, (int)waypoints_.size());
|
||||
if(waypoints_.size() > 1)
|
||||
{
|
||||
for(int i = 0; i < waypoints_.size() - 1; i++)
|
||||
{
|
||||
double x1 = waypoints_[i].pose.pose.position.x;
|
||||
double y1 = waypoints_[i].pose.pose.position.y;
|
||||
double x2 = waypoints_[i+1].pose.pose.position.x;
|
||||
double y2 = waypoints_[i+1].pose.pose.position.y;
|
||||
double theta = atan2(y2 - y1, x2 - x1);
|
||||
tf2::Quaternion temp;
|
||||
temp.setRPY(0, 0, theta);
|
||||
waypoints_[i+1].pose.pose.orientation.x = temp.getX();
|
||||
waypoints_[i+1].pose.pose.orientation.y = temp.getY();
|
||||
waypoints_[i+1].pose.pose.orientation.z = temp.getZ();
|
||||
waypoints_[i+1].pose.pose.orientation.w = temp.getW();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
tf::StampedTransform transform;
|
||||
try
|
||||
{
|
||||
listener_.lookupTransform(frame_id_, base_frame_id_, ros::Time(0), transform);
|
||||
}
|
||||
catch (tf::TransformException &ex)
|
||||
{
|
||||
ROS_ERROR("%s",ex.what());
|
||||
ros::Duration(1.0).sleep();
|
||||
return;
|
||||
}
|
||||
double x1 = transform.getOrigin().x();
|
||||
double y1 = transform.getOrigin().y();
|
||||
double x2 = waypoints_[0].pose.pose.position.x;
|
||||
double y2 = waypoints_[0].pose.pose.position.y;
|
||||
double theta = atan2(y2 - y1, x2 - x1);
|
||||
tf2::Quaternion temp;
|
||||
temp.setRPY(0, 0, theta);
|
||||
waypoints_[0].pose.pose.orientation.x = temp.getX();
|
||||
waypoints_[0].pose.pose.orientation.y = temp.getY();
|
||||
waypoints_[0].pose.pose.orientation.z = temp.getZ();
|
||||
waypoints_[0].pose.pose.orientation.w = temp.getW();
|
||||
}
|
||||
this->pub_waypoints_list();
|
||||
}
|
||||
|
||||
void FollowWayPoints::send_move_base_goal(geometry_msgs::PoseWithCovarianceStamped pose)
|
||||
{
|
||||
move_base_msgs::MoveBaseGoal goal;
|
||||
goal.target_pose.header.frame_id = frame_id_;
|
||||
goal.target_pose.pose.position = pose.pose.pose.position;
|
||||
goal.target_pose.pose.orientation = pose.pose.pose.orientation;
|
||||
ROS_INFO("Executing move_base goal -> (%f, %f) ...", pose.pose.pose.position.x, pose.pose.pose.position.y);
|
||||
if(move_base_client_ != NULL) move_base_client_->sendGoal(goal);
|
||||
}
|
||||
|
||||
void FollowWayPoints::run_once()
|
||||
{
|
||||
if(!path_ready_)
|
||||
{
|
||||
ros::Duration(1.0).sleep();
|
||||
return;
|
||||
}
|
||||
if(waypoints_.empty())
|
||||
{
|
||||
ROS_WARN("No more waypoints to follow.");
|
||||
path_ready_ = false;
|
||||
return;
|
||||
}
|
||||
|
||||
ROS_INFO("Following path with # %d waypoints...", (int)waypoints_.size());
|
||||
tf::StampedTransform transform;
|
||||
try
|
||||
{
|
||||
listener_.lookupTransform(frame_id_, base_frame_id_, ros::Time(0), transform);
|
||||
}
|
||||
catch (tf::TransformException &ex)
|
||||
{
|
||||
ROS_ERROR("%s",ex.what());
|
||||
ros::Duration(1.0).sleep();
|
||||
return;
|
||||
}
|
||||
double x1 = transform.getOrigin().x();
|
||||
double y1 = transform.getOrigin().y();
|
||||
double x2 = waypoints_[0].pose.pose.position.x;
|
||||
double y2 = waypoints_[0].pose.pose.position.y;
|
||||
double theta = atan2(y2 - y1, x2 - x1);
|
||||
tf2::Quaternion temp;
|
||||
temp.setRPY(0, 0, theta);
|
||||
waypoints_[0].pose.pose.orientation.x = temp.getX();
|
||||
waypoints_[0].pose.pose.orientation.y = temp.getY();
|
||||
waypoints_[0].pose.pose.orientation.z = temp.getZ();
|
||||
waypoints_[0].pose.pose.orientation.w = temp.getW();
|
||||
|
||||
// we have waypoints, let's follow them!
|
||||
while (!waypoints_.empty() && ros::ok())
|
||||
{
|
||||
geometry_msgs::PoseWithCovarianceStamped goal = waypoints_.front();
|
||||
if(dyn_config_.patrol_mode)
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
// not in patrol mode - forget about this waypoint
|
||||
waypoints_.erase(waypoints_.begin());
|
||||
}
|
||||
send_move_base_goal(goal);
|
||||
if(!(distance_tolerance_ > 0.0))
|
||||
{
|
||||
// just wait until move_base reaches the goal...
|
||||
if(move_base_client_ != NULL) move_base_client_->waitForResult();
|
||||
ROS_INFO("Waiting for %f seconds before proceeding to the next goal...", wait_duration_);
|
||||
ros::Duration(wait_duration_).sleep();
|
||||
}
|
||||
else
|
||||
{
|
||||
/**
|
||||
raise NotImplementedError("distance_tolerance not implemented yet.")
|
||||
|
||||
TODO - Rewrite
|
||||
This is the loop which exist when the robot is near a certain GOAL point.
|
||||
*/
|
||||
double distance = 10.0;
|
||||
while(distance > distance_tolerance_)
|
||||
{
|
||||
try
|
||||
{
|
||||
listener_.lookupTransform(frame_id_, base_frame_id_, ros::Time(0), transform);
|
||||
}
|
||||
catch (tf::TransformException &ex)
|
||||
{
|
||||
ROS_ERROR("%s",ex.what());
|
||||
ros::Duration(1.0).sleep();
|
||||
continue;
|
||||
}
|
||||
distance = sqrt(
|
||||
pow(goal.pose.pose.position.x - transform.getOrigin().x(), 2) +
|
||||
pow(goal.pose.pose.position.y - transform.getOrigin().y(), 2)
|
||||
);
|
||||
ros::spinOnce();
|
||||
}
|
||||
}
|
||||
// current waypoint has now been reached! move on to the next waypoint on the next
|
||||
// iteration
|
||||
this->pub_waypoints_list();
|
||||
ros::spinOnce();
|
||||
loop_rate_->sleep();
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void FollowWayPoints::run()
|
||||
{
|
||||
while (ros::ok())
|
||||
{
|
||||
this->run_once();
|
||||
ros::spinOnce();
|
||||
}
|
||||
}
|
||||
|
||||
geometry_msgs::PoseWithCovarianceStamped FollowWayPoints::to_pose_with_Cov(geometry_msgs::PointStamped point)
|
||||
{
|
||||
geometry_msgs::PoseWithCovarianceStamped pose;
|
||||
pose.header = point.header;
|
||||
pose.pose.pose.position = point.point;
|
||||
geometry_msgs::Quaternion angle;
|
||||
angle.x = 0;
|
||||
angle.y = 0;
|
||||
angle.z = 0;
|
||||
angle.w = 1;
|
||||
pose.pose.pose.orientation = angle;
|
||||
return pose;
|
||||
}
|
||||
|
||||
geometry_msgs::PoseArray FollowWayPoints::toPoseArray(std::vector<geometry_msgs::PoseWithCovarianceStamped> waypoints)\
|
||||
{
|
||||
geometry_msgs::PoseArray poses;
|
||||
poses.header.frame_id = frame_id_;
|
||||
for(int i = 0; i < waypoints_.size(); i++)
|
||||
poses.poses.insert(poses.poses.begin() , waypoints_[i].pose.pose);
|
||||
return poses;
|
||||
}
|
||||
|
||||
}
|
||||
14
navigations/follow_waypoints/src/follow_waypoints_node.cpp
Executable file
14
navigations/follow_waypoints/src/follow_waypoints_node.cpp
Executable file
@@ -0,0 +1,14 @@
|
||||
#include <ros/ros.h>
|
||||
#include "follow_waypoints/follow_waypoints.h"
|
||||
|
||||
void dyn_callback(follow_waypoints::FollowWayPointsConfig &config, int32_t level);
|
||||
|
||||
int main(int argc, char** argv){
|
||||
ros::init(argc, argv, "follow_waypoints_node");
|
||||
ros::NodeHandlePtr nh = boost::make_shared<ros::NodeHandle>();
|
||||
follow_waypoints::FollowWayPoints* foll = new follow_waypoints::FollowWayPoints(nh, "follow_waypoints_node");
|
||||
foll->run();
|
||||
ros::spin();
|
||||
return(0);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user