3.10 坐标导航
1.编写代码
新建文件nav_clienr.cpp编写代码
#include<ros/ros.h>
#include<move_base_msgs/MoveBaseAction.h>
#include<actionlib/client/simple_action_client.h>typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;int main(int argc, char *argv[])
{ros::init(argc,argv,"nav_client");//这里为true自动阻塞,调用结果MoveBaseClient ac("move_base",true);//等待服务时间为-5swhile(!ac.waitForServer(ros::Duration(5.0))){ROS_INFO("Waiting for the move_base action server to come up");}move_base_msgs::MoveBaseGoal goal;goal.target_pose.header.frame_id="map";goal.target_pose.header.stamp=ros::Time::now();//map 为原点goal.target_pose.pose.position.x=-3.0;goal.target_pose.pose.position.y=2.0;//目标姿态goal.target_pose.pose.orientation.w=1.0;ROS_INFO("Sending goal");ac.sendGoal(goal);ac.waitForResult();if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)ROS_INFO("Mission complete---*u*");elseROS_INFO("Mission failed---TuT");return 0;
}
文件路径为
在CMakeLists.txt增加编译规则
add_executable(nav_client src/nav_client.cpp)
add_dependencies(nav_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(nav_client${catkin_LIBRARIES}
)
2.启动仿真环境
新建3个终端,分别执行命令
roslaunch wpr_simulation wpb_stage_robocup.launch
roslaunch nav_pkg nav.launch
rosrun nav_pkg nav_client
可视化结果
3.航点导航插件
下载插件
git clone https://github.com/6-robot/waterplus_map_tools.gi
进入脚本文件安装依赖
cd waterplus_map_tools/scripts/
执行新建航点程序(地图文件默认在~/catkin_ws/src/wpr_simulation/maps)
roslaunch waterplus_map_tools add_waypoint_simulation.launch
add waypoint 一共增加4个节点
新建终端保存航点
rosrun waterplus_map_tools wp_saver
新建终端,执行命令
roslaunch wpr_simulation wpb_map_tool.launch
可视化结果,机器人在门口
新建终端,执行 航点导航程序
rosrun wpr_simulation demo_map_tool
修改nav.launch文件
<launch><node pkg="move_base" type="move_base" name="move_base"><rosparam file="$(find wpb_home_tutorials)/nav_lidar/costmap_common_params.yaml" command="load" ns="global_costmap" /><rosparam file="$(find wpb_home_tutorials)/nav_lidar/costmap_common_params.yaml" command="load" ns="local_costmap" /><rosparam file="$(find wpb_home_tutorials)/nav_lidar/global_costmap_params.yaml" command="load" /><rosparam file="$(find wpb_home_tutorials)/nav_lidar/local_costmap_params.yaml" command="load" /><param name="base_global_planner" value="global_planner/GlobalPlanner" /> <param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" /><rosparam file="$(find wpb_home_tutorials)/nav_lidar/dwa_local_planner_params.yaml" command="load"/></node><node pkg="map_server" type="map_server" name="map_server" args="$(find wpr_simulation)/maps/map.yaml"/><node pkg="amcl" type="amcl" name="amcl"/><node pkg="rviz" type="rviz" name="rviz" args="-d $(find nav_pkg)/rviz/map_tool.rviz"/><node pkg="waterplus_map_tools" type="wp_navi_server" name="wp_navi_server" output="screen"/><node pkg="waterplus_map_tools" type="wp_manager" name="wp_manager" output="screen"/></launch>
启动仿真环境:新建3个终端,分别执行下列命令
roslaunch wpr_simulation wpb_stage_robocup.launch
roslaunch nav_pkg nav.launch
rosrun wpr_simulation demo_map_tool
航点导航结果可视化
4.航点导航代码编写
启动仿真环境:新建3个终端,分别执行下列命令
roslaunch wpr_simulation wpb_stage_robocup.launch
roslaunch nav_pkg nav.launch
rosrun nav_pkg wp_node
可视化结果
修改msg.data="2",重新编译并运行
rosrun nav_pkg wp_node
机器人前往航点2