A-1 直進し、正面に壁が近づいたら停止する
#include <ros/ros.h> #include <nav_msgs/Odometry.h> #include <geometry_msgs/Twist.h> #include <sensor_msgs/LaserScan.h> #include <tf/transform_datatypes.h> class RSJRobotTestNode { private: ros::Subscriber sub_odom_; ros::Subscriber sub_scan_; ros::Publisher pub_twist_; sensor_msgs::LaserScan latest_scan_; void cbOdom(const nav_msgs::Odometry::ConstPtr &msg) { } void cbScan(const sensor_msgs::LaserScan::ConstPtr &msg) { // 受け取ったメッセージをコピーしておく latest_scan_ = *msg; } public: RSJRobotTestNode() { ros::NodeHandle nh; pub_twist_ = nh.advertise<geometry_msgs::Twist>( "cmd_vel", 5); sub_odom_ = nh.subscribe("odom", 5, &RSJRobotTestNode::cbOdom, this); sub_scan_ = nh.subscribe("scan", 5, &RSJRobotTestNode::cbScan, this); } void mainloop() { ROS_INFO("Hello ROS World!"); ros::Rate rate(10.0); while (ros::ok()) { ros::spinOnce(); if (latest_scan_.ranges.size() > 0) { // LaserScanメッセージをすでに受け取っている場合a geometry_msgs::Twist cmd_vel; int i = (-latest_scan_.angle_min) / latest_scan_.angle_increment; if (latest_scan_.ranges[i] < latest_scan_.range_min || // エラー値の場合 latest_scan_.ranges[i] > latest_scan_.range_max || // 測定範囲外の場合 std::isnan(latest_scan_.ranges[i])) // 無限遠の場合 { // 正面に十分な距離がある (測定範囲以上) ROS_INFO("front-range: measurement error"); cmd_vel.linear.x = 0.2; cmd_vel.angular.z = 0.0; } else { ROS_INFO("front-range: %0.3f", latest_scan_.ranges[i]); if (latest_scan_.ranges[i] > 0.5) { // 50cm以上距離がある cmd_vel.linear.x = 0.2; cmd_vel.angular.z = 0.0; } else { // 50cm以下になった cmd_vel.linear.x = 0.0; cmd_vel.angular.z = 0.0; } } pub_twist_.publish(cmd_vel); } rate.sleep(); } } }; int main(int argc, char* argv[]) { ros::init(argc, argv, "rsj_robot_test_node"); RSJRobotTestNode robot_test; robot_test.mainloop(); }
センサ正面方向の1点のみの距離を取得し、のこりの距離が0.5mより大きい場合は前進、0.5m以下になったら停止します。正面1方向のみでなく、距離を確認する範囲に幅を持たせると、より確実に障害物の手前で止まれるようになります。
A-2 曲がり角を含む壁に沿って走行する
#include <ros/ros.h> #include <nav_msgs/Odometry.h> #include <geometry_msgs/Twist.h> #include <sensor_msgs/LaserScan.h> #include <tf/transform_datatypes.h> class RSJRobotTestNode { private: ros::Subscriber sub_odom_; ros::Subscriber sub_scan_; ros::Publisher pub_twist_; sensor_msgs::LaserScan latest_scan_; float left_prev_; geometry_msgs::Twist cmd_vel_; void cbOdom(const nav_msgs::Odometry::ConstPtr &msg) { } void cbScan(const sensor_msgs::LaserScan::ConstPtr &msg) { // 受け取ったメッセージをコピーしておく latest_scan_ = *msg; } public: RSJRobotTestNode() { ros::NodeHandle nh; pub_twist_ = nh.advertise<geometry_msgs::Twist>( "cmd_vel", 5); sub_odom_ = nh.subscribe("odom", 5, &RSJRobotTestNode::cbOdom, this); sub_scan_ = nh.subscribe("scan", 5, &RSJRobotTestNode::cbScan, this); } void mainloop() { ROS_INFO("Hello ROS World!"); ros::Rate rate(10.0); left_prev_ = FLT_MAX; while (ros::ok()) { ros::spinOnce(); if (latest_scan_.ranges.size() > 0) { // LaserScanメッセージをすでに受け取っている場合 float front = FLT_MAX, left = FLT_MAX; // theta-range 座標系から x-y 座標系に変換 for(unsigned int i = 0; i < latest_scan_.ranges.size(); i ++) { if (!(latest_scan_.ranges[i] < latest_scan_.range_min || latest_scan_.ranges[i] > latest_scan_.range_max || std::isnan(latest_scan_.ranges[i]))) { // 距離値がエラーでない場合 float theta = latest_scan_.angle_min + i * latest_scan_.angle_increment; // x-y 座標系に変換 float x = latest_scan_.ranges[i] * cosf(theta); float y = latest_scan_.ranges[i] * sinf(theta); if (fabs(y) < 0.25 && x > 0.05) { // ロボット正面方向のデータについて最小距離を計算 if (front > x) front = x; } else if (fabs(x) < 0.25 && y > 0.25) { // ロボット左方向のデータについて最小距離を計算 if (left > y) left = y; } } } if (front > 0.5) { // 正面の距離に余裕がある場合 ROS_INFO("Following left wall (distance %0.3f)", left); cmd_vel_.linear.x = 0.1; if (left > 1.0) left = 1.0; // 角速度指令値を0に近づけるようにフィードバック cmd_vel_.angular.z += -cmd_vel_.angular.z * 0.01; // 左方向の距離を0.5mに近づけるようにフィードバック cmd_vel_.angular.z += (left - 0.5) * 0.02; // 距離の変化量(壁の向きを表す)を0に近づけるようにフィードバック if (left_prev_ < 1.0) cmd_vel_.angular.z += (left - left_prev_) * 4.0; if (cmd_vel_.angular.z > 0.3) cmd_vel_.angular.z = 0.3; else if (cmd_vel_.angular.z < -0.3) cmd_vel_.angular.z = -0.3; } else { ROS_INFO("Something in front"); cmd_vel_.linear.x = 0.0; cmd_vel_.angular.z = -0.2; } left_prev_ = left; pub_twist_.publish(cmd_vel_); } rate.sleep(); } } }; int main(int argc, char* argv[]) { ros::init(argc, argv, "rsj_robot_test_node"); RSJRobotTestNode robot_test; robot_test.mainloop(); }
ロボットの左側約0.5mに壁がある状態からスタートすることで動作を確認できます。
左方向の物体までの距離を測定し、これを0.5mにする(つまり、壁から 0.5mの位置を走る)ように制御します。壁からの距離の誤差、距離の誤差の微分値(壁の向きに対するロボットの向きを表す)、角速度指令値に適当なゲインをかけて、角加速度にフィードバックしています。すなわち、これは、講義1中で説明した、直線追従制御系の簡易的な実装になっています。また、正面がふさがっている場合は、右に旋回することで、常に左の壁に沿って走行を続けます。