这是LZ在Pioneer3at上运行gmapping的一个教程,首先假设小伙伴已经成功在自己的机器人上运行了move_base部分,然后接着上篇博客继续.
首先还是启动对应机器人的launch文件
roslaunch felaim_2dnav felaim_robot.launch
因为LZ不想依靠更多的传感器,只能依靠kinect,所以要把kinect采集到的转换成激光数据,所以启动的节点是先连接kinect,然后运行depthimage_to_laser节点,转化成laser数据.
roslaunch felaim_2dnav pioneer3at_fake_laser_freenect.launch
对fake_laser进行可视化显示,我们可以使用
rosrun rviz rviz -d `rospack find felaim_2dnav`/launch/fake_laser.rviz
具体的显示结果如下图所示:
我们接下来要运行gmapping部分了
roslaunch felaim_2dnav gmapping_demo.launch
gmapping_demo.launch
<launch>
<include file="$(find felaim_2dnav)/launch/gmapping.launch"/>
<include file="$(find felaim_2dnav)/launch/tb_move_base.launch"/>
</launch>
gmapping.launch
<launch>
<arg name="scan_topic" default="scan" />
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen" clear_params="true">
<param name="odom_frame" value="odom"/>
<param name="map_update_interval" value="30.0"/>
<!-- Set maxUrange < actual maximum range of the Laser -->
<param name="maxRange" value="5.0"/>
<param name="maxUrange" value="4.5"/>
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="lskip" value="0"/>
<param name="srr" value="0.01"/>
<param name="srt" value="0.02"/>
<param name="str" value="0.01"/>
<param name="stt" value="0.02"/>
<param name="linearUpdate" value="0.5"/>
<param name="angularUpdate" value="0.436"/>
<param name="temporalUpdate" value="-1.0"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="80"/>
<!--
<param name="xmin" value="-50.0"/>
<param name="ymin" value="-50.0"/>
<param name="xmax" value="50.0"/>
<param name="ymax" value="50.0"/>
make the starting size small for the benefit of the Android client's memory...
-->
<param name="xmin" value="-1.0"/>
<param name="ymin" value="-1.0"/>
<param name="xmax" value="1.0"/>
<param name="ymax" value="1.0"/>
<param name="delta" value="0.05"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
</launch>
tb_move_base.launch
<launch>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
<rosparam file="$(find felaim_2dnav)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find felaim_2dnav)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find felaim_2dnav)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find felaim_2dnav)/config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find felaim_2dnav)/config/base_local_planner_params.yaml" command="load" />
</node>
</launch>
LZ这里贴出了主要的launch文件,小伙伴们需要根据自己实际的情况进行修改
LZ这里提供一个键盘控制机器人运动的c++代码,用catkin_make编译通过就可使用
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <signal.h>
#include <termios.h>
#include <stdio.h>
#define KEYCODE_R 0x43
#define KEYCODE_L 0x44
#define KEYCODE_U 0x41
#define KEYCODE_D 0x42
#define KEYCODE_A 0x61
#define KEYCODE_Z 0x7A
#define KEYCODE_S 0x73
#define KEYCODE_X 0x78
#define KEYCODE_Q 0x71
#define KEYCODE_SPACE 0x20
class TeleopRosAria
{
public:
TeleopRosAria();
void keyLoop();
private:
ros::NodeHandle nh_;
double linear_, angular_, l_scale_, a_scale_;
double current_linear_, current_angular_, step_linear_, step_angular_;
ros::Publisher twist_pub_;
};
TeleopRosAria::TeleopRosAria():
linear_(0),
angular_(0),
l_scale_(2.0),
a_scale_(2.0),
current_angular_(0.1),
current_linear_(0.1),
step_linear_(0.2),
step_angular_(0.1)
{
nh_.param("scale_angular", a_scale_, a_scale_);
nh_.param("scale_linear", l_scale_, l_scale_);
twist_pub_ = nh_.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
}
int kfd = 0;
struct termios cooked, raw;
void quit(int sig)
{
tcsetattr(kfd, TCSANOW, &cooked);
ros::shutdown();
exit(0);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "teleop_RosAria");
TeleopRosAria teleop_RosAria;
signal(SIGINT,quit);
teleop_RosAria.keyLoop();
return(0);
}
void TeleopRosAria::keyLoop()
{
char c;
bool dirty=false;
// get the console in raw mode
tcgetattr(kfd, &cooked);
memcpy(&raw, &cooked, sizeof(struct termios));
raw.c_lflag &=~ (ICANON | ECHO);
// Setting a new line, then end of file
raw.c_cc[VEOL] = 1;
raw.c_cc[VEOF] = 2;
tcsetattr(kfd, TCSANOW, &raw);
puts("Reading from keyboard");
puts("---------------------------");
puts("Use arrow keys to move the robot.");
puts("Press the space bar to stop the robot.");
puts("Press q to stop the program");
puts("a/z - Increase/decrease linear velocity");
puts("s/x - Increase/decrease angular velocity");
for(;;)
{
// get the next event from the keyboard
if(read(kfd, &c, 1) < 0)
{
perror("read():");
exit(-1);
}
linear_=angular_=0;
char printable[100];
ROS_DEBUG("value: 0x%02X\n", c);
switch(c)
{
case KEYCODE_L:
ROS_DEBUG("LEFT");
angular_ = current_angular_;
linear_ = 0;
dirty = true;
break;
case KEYCODE_R:
ROS_DEBUG("RIGHT");
angular_ = -current_angular_;
linear_ = 0;
dirty = true;
break;
case KEYCODE_U:
ROS_DEBUG("UP");
linear_ = current_linear_;
angular_ = 0;
dirty = true;
break;
case KEYCODE_D:
ROS_DEBUG("DOWN");
linear_ = -current_linear_;
angular_ = 0;
dirty = true;
break;
case KEYCODE_A:
ROS_DEBUG("INCREASE LINEAR SPEED");
current_linear_ += step_linear_;
sprintf(printable, "Linear speed: %02f", current_linear_);
puts(printable);
dirty=true;
break;
case KEYCODE_Z:
ROS_DEBUG("DECREASE LINEAR SPEED");
current_linear_ -= step_linear_;
if(current_linear_ < 0)
current_linear_ = 0;
sprintf(printable, "Linear speed: %02f", current_linear_);
puts(printable);
dirty=true;
break;
case KEYCODE_S:
ROS_DEBUG("INCREASE ANGULAR SPEED");
current_angular_ += step_angular_;
sprintf(printable, "Angular speed: %02f", current_angular_);
puts(printable);
dirty=true;
break;
case KEYCODE_X:
ROS_DEBUG("DECREASE LINEAR SPEED");
current_angular_ -= step_angular_;
if(current_angular_ < 0)
current_angular_ = 0;
sprintf(printable, "Angular speed: %02f", current_angular_);
puts(printable);
dirty=true;
break;
case KEYCODE_SPACE:
ROS_DEBUG("STOP");
linear_ = 0;
angular_ = 0;
dirty = true;
break;
case KEYCODE_Q:
ROS_DEBUG("QUIT");
ROS_INFO_STREAM("You quit the teleop successfully");
return;
break;
}
geometry_msgs::Twist twist;
twist.angular.z = a_scale_*angular_;
twist.linear.x = l_scale_*linear_;
if(dirty ==true)
{
twist_pub_.publish(twist);
dirty=false;
}
}
return;
}
使用键盘控制自己的机器人到你想要创建地图的地方,(当机器人移动时,在RVIZ中的扫描点会反映出机器人附近环境的变化,记得重复检查Fixed Frame已经通过Global Options设定在odom框架)
对gmapping进行可视化
rosrun rviz rviz -d `rospack find felaim_2dnav`/launch/gmapping.rviz
把数据记录到一个包文件中,新建一个文件夹bag_files
roscd felaim_2dnav/bag_files
//my_scan_data是LZ取的包名,小伙伴们可以根据自己的喜好进行修改
//输入的是tf和转换的laser数据
rosbag record -O my_scan_data /scan /tf
在ctrl+c后结束记录后,通过map_sever进行地图创建
为了保存地图,我们还是可以新建一个文件夹用来放地图maps
roscd felaim_2dnav/maps
//取的名字是my_map,可以自行修改啦
rosrun map_sever map_saver -f my_map
//通过eye of Gnome查看保存的地图
eog my_map_pgm
走廊的建图:
感觉还是有些漂…O(∩_∩)O哈哈~继续努力~(≧▽≦)/~啦啦啦