turtlebot2利用turtlebot_exploration_3d进行自主建图

2023-05-16

  • 安装octomap_ros和rviz插件
    sudo apt-get install ros-indigo-octomap*
    
  • 源码安装:turtlebot_exploration_3d(本机为Ubuntu16对应的ros版本为kinetic,但是无对应的版本,用的是ubuntu14的indigo,版本向前兼容,故可以运行)
  • cd turtlebot_ws/src
    git clone https://github.com/RobustFieldAutonomyLab/turtlebot_exploration_3d.git
    catkin_make
    
  • deb包安装:
  • sudo apt-get update
    sudo apt-get install ros-indigo-turtlebot-exploration-3d
    

    运行:

  • 主机端,新终端,执行:
  • $ roslaunch turtlebot_exploration_3d minimal_explo.launch
    $ roslaunch turtlebot_exploration_3d turtlebot_gmapping.launch
    $ rosrun turtlebot_exploration_3d turtlebot_exploration_3d
    
  • 从机端,新终端,执行:
  • roslaunch turtlebot_exploration_3d exploration_rviz.launch
    

对应的脚本信息如下:

minimal_explo.launch:

<launch>
  <!-- Turtlebot -->

  <arg name="base"             default="$(env TURTLEBOT_BASE)"/>  <!-- create, roomba -->
  <arg name="battery"          default="$(env TURTLEBOT_BATTERY)"/>  <!-- /proc/acpi/battery/BAT0 in 2.6 or earlier kernels-->
  <arg name="stacks"           default="$(env TURTLEBOT_STACKS)"/>  <!-- circles, hexagons -->
  <arg name="3d_sensor"        default="$(env TURTLEBOT_3D_SENSOR)"/>  <!-- kinect, asus_xtion_pro -->
  <arg name="simulation"       default="$(env TURTLEBOT_SIMULATION)"/>
  <arg name="serialport"       default="$(env TURTLEBOT_SERIAL_PORT)"/> <!-- /dev/ttyUSB0, /dev/ttyS0 -->
  <arg name="robot_name"       default="$(env TURTLEBOT_NAME)"/>
  <arg name="robot_type"       default="$(env TURTLEBOT_TYPE)"/>

  <param name="/use_sim_time" value="$(arg simulation)"/>

  <include file="$(find turtlebot_bringup)/launch/includes/robot.launch.xml">
    <arg name="base" value="$(arg base)" />
    <arg name="stacks" value="$(arg stacks)" />
    <arg name="3d_sensor" value="$(arg 3d_sensor)" />
  </include>
  <include file="$(find turtlebot_bringup)/launch/includes/mobile_base.launch.xml">
    <arg name="base" value="$(arg base)" />
    <arg name="serialport" value="$(arg serialport)" />
  </include>
  <include file="$(find turtlebot_bringup)/launch/includes/netbook.launch.xml">
    <arg name="battery" value="$(arg battery)" />
  </include>

  <!-- Rapp Manager --> 
  <arg name="auto_rapp_installation"            default="false"/> <!-- http://wiki.ros.org/rocon_app_manager/Tutorials/indigo/Automatic Rapp Installation -->
  <arg name="auto_start_rapp"                   default=""/> <!-- autostart a rapp, e.g. rocon_apps/talker -->
  <arg name="rapp_package_whitelist"            default="$(env TURTLEBOT_RAPP_PACKAGE_WHITELIST)"/> <!-- comma separated list of package names -->
  <arg name="rapp_package_blacklist"            default="$(env TURTLEBOT_RAPP_PACKAGE_BLACKLIST)"/>
  <arg name="robot_icon"                        default="turtlebot_bringup/turtlebot2.png"/>
  <arg name="screen"                            default="true"/> <!-- verbose output from running apps -->

  <!-- ***************************** Rocon Master Info ************************** -->
  <arg name="robot_description"                 default="Kick-ass ROS turtle"/>

  <!-- Capabilities --> 
  <arg name="capabilities"                      default="true"/> <!-- enable/disable a capability server -->
  <arg name="capabilities_server_name"          default="capability_server"/>
  <arg name="capabilities_nodelet_manager_name" default="capability_server_nodelet_manager" />
  <arg name="capabilities_parameters"           default="$(find turtlebot_bringup)/param/capabilities/defaults_tb2.yaml" /> <!-- defaults_tb.yaml, defaults_tb2.yaml -->
  <arg name="capabilities_package_whitelist"    default="[kobuki_capabilities, std_capabilities, turtlebot_capabilities]" /> <!-- get capabilities from these packages only -->
  <arg name="capabilities_blacklist"            default="['std_capabilities/Navigation2D', 'std_capabilities/MultiEchoLaserSensor']" /> <!-- blacklist specific capabilities -->

  <!-- Interactions --> 
  <arg name="interactions"      default="true"/>
  <arg name="interactions_list" default="$(optenv INTERACTIONS_LIST [turtlebot_bringup/admin.interactions, turtlebot_bringup/documentation.interactions, turtlebot_bringup/pairing.interactions])"/>

  <!-- Zeroconf -->
  <arg name="zeroconf"                          default="true"/>
  <arg name="zeroconf_name"                     default="$(arg robot_name)"/>
  <arg name="zeroconf_port"                     default="11311"/>

  <!-- Rapp Manager -->
  <include file="$(find rocon_app_manager)/launch/standalone.launch">

    <!-- Rapp Manager --> 
    <arg name="robot_name"                        value="$(arg robot_name)" />
    <arg name="robot_type"                        value="$(arg robot_type)" />
    <arg name="robot_icon"                        value="$(arg robot_icon)" />
    <arg name="rapp_package_whitelist"            value="$(arg rapp_package_whitelist)" />
    <arg name="rapp_package_blacklist"            value="$(arg rapp_package_blacklist)" />
    <arg name="auto_start_rapp"                   value="$(arg auto_start_rapp)" />
    <arg name="screen"                            value="$(arg screen)" />
    <arg name="auto_rapp_installation"            value="$(arg auto_rapp_installation)" />

    <!-- Rocon Master Info -->
    <arg name="robot_description"                 value="$(arg robot_description)" />

    <!-- Capabilities --> 
    <arg name="capabilities"                      value="$(arg capabilities)" />
    <arg name="capabilities_blacklist"            value="$(arg capabilities_blacklist)" />
    <arg name="capabilities_nodelet_manager_name" value="$(arg capabilities_nodelet_manager_name)" />
    <arg name="capabilities_server_name"          value="$(arg capabilities_server_name)" />
    <arg name="capabilities_package_whitelist"    value="$(arg capabilities_package_whitelist)" />
    <arg name="capabilities_parameters"           value="$(arg capabilities_parameters)" />

    <!-- Interactions --> 
    <arg name="interactions"                      value="$(arg interactions)"/>
    <arg name="interactions_list"                 value="$(arg interactions_list)"/>

    <!-- Zeroconf --> 
    <arg name="zeroconf"                          value="$(arg zeroconf)"/>
    <arg name="zeroconf_name"                     value="$(arg zeroconf_name)"/>
    <arg name="zeroconf_port"                     value="$(arg zeroconf_port)"/>

  </include>



</launch>

turtlebot_gmapping.launch:

<launch>
<!--   <node pkg="hokuyo_node" type="hokuyo_node" name="hokuyo" />
 -->
  <include file="$(find turtlebot_bringup)/launch/3dsensor.launch">
  <!--  <arg name="rgb_processing" value="true" />
    <arg name="depth_registration" value="true" />
    <arg name="depth_processing" value="true" />
    <arg name="scan_processing" value="true" />           -->
    
    <!-- We must specify an absolute topic name because if not it will be prefixed by "$(arg camera)".
         Probably is a bug in the nodelet manager: https://github.com/ros/nodelet_core/issues/7 --> 
    <arg name="scan_topic" value="/scan_kinect" />
  </include>

  <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser" args="0 0 0.35 0 0 0 base_footprint laser 50" />
  
  <arg name="scan_topic"  default="scan_kinect" />
  <arg name="base_frame"  default="base_footprint"/>
  <arg name="odom_frame"  default="odom"/>

  <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
    <param name="scan_topic" value="$(arg scan_topic)"/>
    <param name="base_frame" value="$(arg base_frame)"/>
    <param name="odom_frame" value="$(arg odom_frame)"/>
    <param name="map_update_interval" value="5.0"/>
    <param name="maxUrange" value="7.9"/>
    <param name="maxRange" value="8.0"/>
    <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="minimumScore" value="200"/>
    <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.01"/>
    <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>

  <include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml"/>

  <node pkg="turtlebot_exploration_3d" type="scan_to_pcl" name="scan_to_pcl" />


</launch>

 turtlebot_exploration_3d.cpp:

// Related headers:
#include "exploration.h"
#include "navigation_utils.h"
#include "gpregressor.h"
#include "covMaterniso3.h"

//C library headers:
#include <iostream>
#include <fstream>
// #include <chrono>
// #include <iterator>
// #include <ctime>

//C++ library headers:  NONE
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>

//other library headers:  NONE


using namespace std;


int main(int argc, char **argv) {
    ros::init(argc, argv, "turtlebot_exploration_3d");
    ros::NodeHandle nh;

    // Initialize time
    time_t rawtime;
    struct tm * timeinfo;
    char buffer[80];
    time (&rawtime);
    timeinfo = localtime(&rawtime);
    // strftime(buffer,80,"Trajectory_%R_%S_%m%d_DA.txt",timeinfo);
    // std::string logfilename(buffer);
    // std::cout << logfilename << endl;

    strftime(buffer,80,"Octomap3D_%m%d_%R_%S.ot",timeinfo);
    octomap_name_3d = buffer;


    ros::Subscriber kinect_sub = nh.subscribe<sensor_msgs::PointCloud2>("/camera/depth_registered/points", 1, kinectCallbacks);// need to change##########
    ros::Publisher GoalMarker_pub = nh.advertise<visualization_msgs::Marker>( "Goal_Marker", 1 );
    ros::Publisher Candidates_pub = nh.advertise<visualization_msgs::MarkerArray>("Candidate_MIs", 1);
    ros::Publisher Frontier_points_pub = nh.advertise<visualization_msgs::Marker>("Frontier_points", 1);
    ros::Publisher pub_twist = nh.advertise<geometry_msgs::Twist>("/cmd_vel_mux/input/teleop", 1);
    ros::Publisher Octomap_pub = nh.advertise<octomap_msgs::Octomap>("octomap_3d",1);


    tf_listener = new tf::TransformListener();
    tf::StampedTransform transform;
    tf::Quaternion Goal_heading; // robot's heading direction

    visualization_msgs::MarkerArray CandidatesMarker_array;
    visualization_msgs::Marker Frontier_points_cubelist;
    geometry_msgs::Twist twist_cmd;

    ros::Time now_marker = ros::Time::now();
   
    // Initialize parameters 
    int max_idx = 0;

    point3d Sensor_PrincipalAxis(1, 0, 0);
    octomap::OcTreeNode *n;
    octomap::OcTree new_tree(octo_reso);
    octomap::OcTree new_tree_2d(octo_reso);
    cur_tree = &new_tree;
    cur_tree_2d = &new_tree_2d;
    point3d next_vp;

    bool got_tf = false;
    bool arrived;
    
    // Update the initial location of the robot
    for(int i =0; i < 6; i++){
        // Update the pose of the robot
        got_tf = false;
        while(!got_tf){
        try{
            tf_listener->lookupTransform("/map", "/camera_rgb_frame", ros::Time(0), transform);// need to change tf of kinect###############
            kinect_orig = point3d(transform.getOrigin().x(), transform.getOrigin().y(), transform.getOrigin().z());
            got_tf = true;
        }
        catch (tf::TransformException ex) {
            ROS_WARN("Wait for tf: Kinect frame"); 
        } 
        ros::Duration(0.05).sleep();
        }

        // Take a Scan
        ros::spinOnce();

        // Rotate another 60 degrees
        twist_cmd.linear.x = twist_cmd.linear.y = twist_cmd.angular.z = 0;
        ros::Time start_turn = ros::Time::now();

        ROS_WARN("Rotate 60 degrees");
        while (ros::Time::now() - start_turn < ros::Duration(2.6)){ // turning duration - second
        twist_cmd.angular.z = 0.6; // turning speed
        // turning angle = turning speed * turning duration / 3.14 * 180
        pub_twist.publish(twist_cmd);
        ros::Duration(0.05).sleep();
        }
        // stop
        twist_cmd.angular.z = 0;
        pub_twist.publish(twist_cmd);

    }

    // steps robot taken, counter
    int robot_step_counter = 0;

    while (ros::ok())
    {
        vector<vector<point3d>> frontier_groups=extractFrontierPoints(cur_tree);
        
        //frontier_groups.clear();//in the next line
        unsigned long int o = 0;
        for(vector<vector<point3d>>::size_type e = 0; e < frontier_groups.size(); e++) {
            o = o+frontier_groups[e].size();
        }

        Frontier_points_cubelist.points.resize(o);
        ROS_INFO("frontier points %ld", o);
        now_marker = ros::Time::now();
        Frontier_points_cubelist.header.frame_id = "map";
        Frontier_points_cubelist.header.stamp = now_marker;
        Frontier_points_cubelist.ns = "frontier_points_array";
        Frontier_points_cubelist.id = 0;
        Frontier_points_cubelist.type = visualization_msgs::Marker::CUBE_LIST;
        Frontier_points_cubelist.action = visualization_msgs::Marker::ADD;
        Frontier_points_cubelist.scale.x = octo_reso;
        Frontier_points_cubelist.scale.y = octo_reso;
        Frontier_points_cubelist.scale.z = octo_reso;
        Frontier_points_cubelist.color.a = 1.0;
        Frontier_points_cubelist.color.r = (double)255/255;
        Frontier_points_cubelist.color.g = 0;
        Frontier_points_cubelist.color.b = (double)0/255;
        Frontier_points_cubelist.lifetime = ros::Duration();

        unsigned long int t = 0;
        int l = 0;
        geometry_msgs::Point q;
        for(vector<vector<point3d>>::size_type n = 0; n < frontier_groups.size(); n++) { 
            for(vector<point3d>::size_type m = 0; m < frontier_groups[n].size(); m++){
               q.x = frontier_groups[n][m].x();
               q.y = frontier_groups[n][m].y();
               q.z = frontier_groups[n][m].z()+octo_reso;
               Frontier_points_cubelist.points.push_back(q); 
               
            }
            t++;
        }
        ROS_INFO("Publishing %ld frontier_groups", t);
        
        Frontier_points_pub.publish(Frontier_points_cubelist); //publish frontier_points
        Frontier_points_cubelist.points.clear();           

        // Generate Candidates
        vector<pair<point3d, point3d>> candidates = extractCandidateViewPoints(frontier_groups, kinect_orig, num_of_samples); 
        std::random_shuffle(candidates.begin(),candidates.end()); // shuffle to select a subset
        vector<pair<point3d, point3d>> gp_test_poses = candidates;
        ROS_INFO("Candidate View Points: %luGenereated, %d evaluating...", candidates.size(), num_of_samples_eva);
        int temp_size = candidates.size()-3;
        if (temp_size < 1) {
            ROS_ERROR("Very few candidates generated, maybe finishing with exploration...");
            nh.shutdown();
            return 0;
        }

        // Generate Testing poses
        candidates.resize(min(num_of_samples_eva,temp_size));
        frontier_groups.clear();

// Evaluate MI for every candidate view points
        vector<double>  MIs(candidates.size());
        double before = countFreeVolume(cur_tree);
        // int max_idx = 0;
        double begin_mi_eva_secs, end_mi_eva_secs;
        begin_mi_eva_secs = ros::Time::now().toSec();

        #pragma omp parallel for
        for(int i = 0; i < candidates.size(); i++) 
        {
            auto c = candidates[i];
            // Evaluate Mutual Information
            Sensor_PrincipalAxis = point3d(1.0, 0.0, 0.0);
            Sensor_PrincipalAxis.rotate_IP(c.second.roll(), c.second.pitch(), c.second.yaw() );
            octomap::Pointcloud hits = castSensorRays(cur_tree, c.first, Sensor_PrincipalAxis);
            
            // Considering pure MI for decision making
            MIs[i] = calc_MI(cur_tree, c.first, hits, before);
            
            // Normalize the MI with distance
            // MIs[i] = calc_MI(cur_tree, c.first, hits, before) / 
            //     sqrt(pow(c.first.x()-kinect_orig.x(),2) + pow(c.first.y()-kinect_orig.y(),2));

            // Pick the Candidate view point with max MI
            // if (MIs[i] > MIs[max_idx])
            // {
            //     max_idx = i;
            // }
        }


        // Bayesian Optimization for actively selecting candidate
        double train_time, test_time;
        GPRegressor g(100, 3, 0.01);
        for (int bay_itr = 0; bay_itr < num_of_bay; bay_itr++) {
            //Initialize gp regression
            
            MatrixXf gp_train_x(candidates.size(), 2), gp_train_label(candidates.size(), 1), gp_test_x(gp_test_poses.size(), 2);

            for (int i=0; i< candidates.size(); i++){
                gp_train_x(i,0) = candidates[i].first.x();
                gp_train_x(i,1) = candidates[i].first.y();
                gp_train_label(i) = MIs[i];
            }

            for (int i=0; i< gp_test_poses.size(); i++){
                gp_test_x(i,0) = gp_test_poses[i].first.x();
                gp_test_x(i,1) = gp_test_poses[i].first.y();
            }

            // Perform GP regression
            MatrixXf gp_mean_MI, gp_var_MI;
            train_time = ros::Time::now().toSec();
            g.train(gp_train_x, gp_train_label);
            train_time = ros::Time::now().toSec() - train_time;

            test_time = ros::Time::now().toSec();
            g.test(gp_test_x, gp_mean_MI, gp_var_MI);
            test_time = ros::Time::now().toSec() - test_time;
            ROS_INFO("GP: Train(%zd) took %f secs , Test(%zd) took %f secs", candidates.size(), train_time, gp_test_poses.size(), test_time);        

            // Get Acquisition function
            double beta = 2.4;
            vector<double>  bay_acq_fun(gp_test_poses.size());
            for (int i = 0; i < gp_test_poses.size(); i++) {
                bay_acq_fun[i] = gp_mean_MI(i) + beta*gp_var_MI(i);
            }
            vector<int> idx_acq = sort_MIs(bay_acq_fun);

            // evaluate MI, add to the candidate
            auto c = gp_test_poses[idx_acq[0]];
            Sensor_PrincipalAxis = point3d(1.0, 0.0, 0.0);
            Sensor_PrincipalAxis.rotate_IP(c.second.roll(), c.second.pitch(), c.second.yaw() );
            octomap::Pointcloud hits = castSensorRays(cur_tree, c.first, Sensor_PrincipalAxis);
            candidates.push_back(c);
            MIs.push_back(calc_MI(cur_tree, c.first, hits, before));
        }
        
        end_mi_eva_secs = ros::Time::now().toSec();
        ROS_INFO("Mutual Infomation Eva took:  %3.3f Secs.", end_mi_eva_secs - begin_mi_eva_secs);

        // Normalize the MI with distance
        for(int i = 0; i < candidates.size(); i++) {
            auto c = candidates[i];
            MIs[i] = MIs[i] / 
                sqrt(pow(c.first.x()-kinect_orig.x(),2) + pow(c.first.y()-kinect_orig.y(),2));
        }

        // sort vector MIs, with idx_MI, descending
        vector<int> idx_MI = sort_MIs(MIs);

        // Publish the candidates as marker array in rviz
        tf::Quaternion MI_heading;
        MI_heading.setRPY(0.0, -PI/2, 0.0);
        MI_heading.normalize();
        
        CandidatesMarker_array.markers.resize(candidates.size());
        for (int i = 0; i < candidates.size(); i++)
        {
            CandidatesMarker_array.markers[i].header.frame_id = "map";
            CandidatesMarker_array.markers[i].header.stamp = ros::Time::now();
            CandidatesMarker_array.markers[i].ns = "candidates";
            CandidatesMarker_array.markers[i].id = i;
            CandidatesMarker_array.markers[i].type = visualization_msgs::Marker::ARROW;
            CandidatesMarker_array.markers[i].action = visualization_msgs::Marker::ADD;
            CandidatesMarker_array.markers[i].pose.position.x = candidates[i].first.x();
            CandidatesMarker_array.markers[i].pose.position.y = candidates[i].first.y();
            CandidatesMarker_array.markers[i].pose.position.z = candidates[i].first.z();
            CandidatesMarker_array.markers[i].pose.orientation.x = MI_heading.x();
            CandidatesMarker_array.markers[i].pose.orientation.y = MI_heading.y();
            CandidatesMarker_array.markers[i].pose.orientation.z = MI_heading.z();
            CandidatesMarker_array.markers[i].pose.orientation.w = MI_heading.w();
            CandidatesMarker_array.markers[i].scale.x = (double)2.0*MIs[i]/MIs[idx_MI[0]];
            CandidatesMarker_array.markers[i].scale.y = 0.2;
            CandidatesMarker_array.markers[i].scale.z = 0.2;
            CandidatesMarker_array.markers[i].color.a = (double)MIs[i]/MIs[idx_MI[0]];
            CandidatesMarker_array.markers[i].color.r = 0.0;
            CandidatesMarker_array.markers[i].color.g = 1.0;
            CandidatesMarker_array.markers[i].color.b = 0.0;
        }
        Candidates_pub.publish(CandidatesMarker_array);
        CandidatesMarker_array.markers.clear();
        candidates.clear();

        // loop in the idx_MI, if the candidate with max MI cannot be achieved, 
        // switch to a sub-optimal MI.
        arrived = false;
        int idx_ptr = 0;

        while (!arrived) {
            // Setup the Goal
            next_vp = point3d(candidates[idx_MI[idx_ptr]].first.x(),candidates[idx_MI[idx_ptr]].first.y(),candidates[idx_MI[idx_ptr]].first.z());
            Goal_heading.setRPY(0.0, 0.0, candidates[idx_MI[idx_ptr]].second.yaw());
            Goal_heading.normalize();
            ROS_INFO("Max MI : %f , @ location: %3.2f  %3.2f  %3.2f", MIs[idx_MI[idx_ptr]], next_vp.x(), next_vp.y(), next_vp.z() );
            
            // Publish the goal as a Marker in rviz
            visualization_msgs::Marker marker;
            marker.header.frame_id = "map";
            marker.header.stamp = ros::Time();
            marker.ns = "goal_marker";
            marker.id = 0;
            marker.type = visualization_msgs::Marker::ARROW;
            marker.action = visualization_msgs::Marker::ADD;
            marker.pose.position.x = next_vp.x();
            marker.pose.position.y = next_vp.y();
            marker.pose.position.z = 1.0;
            marker.pose.orientation.x = Goal_heading.x();
            marker.pose.orientation.y = Goal_heading.y();
            marker.pose.orientation.z = Goal_heading.z();
            marker.pose.orientation.w = Goal_heading.w();
            marker.scale.x = 0.5;
            marker.scale.y = 0.1;
            marker.scale.z = 0.1;
            marker.color.a = 1.0; // Don't forget to set the alpha!
            marker.color.r = 1.0;
            marker.color.g = 1.0;
            marker.color.b = 0.0;
            GoalMarker_pub.publish( marker );

            // Send the Robot 
            arrived = goToDest(next_vp, Goal_heading);

            if(arrived)
            {
                // Update the initial location of the robot
                got_tf = false;
                while(!got_tf){
                try{
                    tf_listener->lookupTransform("/map", "/camera_rgb_frame", ros::Time(0), transform);// need to change tf of kinect###############
                    kinect_orig = point3d(transform.getOrigin().x(), transform.getOrigin().y(), transform.getOrigin().z());
                    got_tf = true;
                }
                catch (tf::TransformException ex) {
                    ROS_WARN("Wait for tf: Kinect frame"); 
                } 
                ros::Duration(0.05).sleep();
                }
                // Update Octomap
                ros::spinOnce();
                ROS_INFO("Succeed, new Map Free Volume: %f", countFreeVolume(cur_tree));
                robot_step_counter++;

                // prepare octomap msg
                octomap_msgs::binaryMapToMsg(*cur_tree, msg_octomap);
                msg_octomap.binary = 1;
                msg_octomap.id = 1;
                msg_octomap.resolution = octo_reso;
                msg_octomap.header.frame_id = "/map";
                msg_octomap.header.stamp = ros::Time::now();
                Octomap_pub.publish(msg_octomap);
                ROS_INFO("Octomap updated in RVIZ");

                // // Send out results to file.
                // explo_log_file.open(logfilename, std::ofstream::out | std::ofstream::app);
                // explo_log_file << "DA Step ," << robot_step_counter << ", Current Entropy ," << countFreeVolume(cur_tree) << ", time, " << ros::Time::now().toSec() << endl;
                // explo_log_file.close();

            }
            else
            {
                ROS_WARN("Failed to drive to the %d th goal, switch to the sub-optimal..", idx_ptr);
                idx_ptr++;
                if(idx_ptr > MIs.size()) {
                    ROS_ERROR("None of the goal is valid for path planning, shuting down the node");
                    nh.shutdown();
                }
            }

        }

        
        // r.sleep();
    }
    nh.shutdown();          
    return 0;
}

 exploration_rviz.launch:

<launch>  
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find turtlebot_exploration_3d)/launch/turtlebot_explo.rviz" />

</launch>

  • 自动建图进行会比较慢,会显示octomap图,同时也实现了gmapping的建图

 

image: /home/ubuntu/map/zhizaokongjian.pgm
resolution: 0.050000
origin: [-12.200000, -12.200000, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196

image:   含占用信息的image文件的路径;可以是绝对路径,也可以是到YAML文件的相对路径。
resolution:地图的分辨率,meters/pixel
origin: 机器人相对地图原点的位姿,(x,y,yaw),yaw逆时针旋转(yaw=0表示没有旋转)。
occupied_thresh:单元占用的概率大于这个阈值则认为完全占用。
free_thresh: 单元占用的概率小于这个阈值则认为完全自由。
negate: 不论白色/黑色,自由/占用,semantics(语义/符号)应该被反转(阈值的解释不受影响)。
  • 保存地图:

  • 新建目录:
  • mkdir ~/map
    
  • 保存地图:
  • rosrun map_server map_saver -f ~/map1
    
  • 得到两个文件如下:

    • map1.pgm 地图
    • map1.yaml 配置
  • map1.yaml样例:

  • 必填的字节:

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

turtlebot2利用turtlebot_exploration_3d进行自主建图 的相关文章

  • Autosar CAN通讯——CANSM

    关于CANSM参考 xff1a https zhuanlan zhihu com p 126073070
  • UDS一些时间参数

    最近在做 xff21 xff55 xff54 xff4f xff53 xff41 xff52 诊断 xff0c 发现在诊断中有一些时间参数需要配置 xff08 其实这个时间参数 xff21 xff55 xff52 xff4f xff53 x
  • sql server 数据库开发 知识点

    sql server 数据库开发 1 含义 xff1a 数据库设计实际上就是规划和结构化数据库中的数据对象以及这些数据对象之间关系的过程 E R图组成包括 xff1a 矩形表示实体集 椭圆表示属性 菱形表示关系 直线用来连接实体集与属性 x
  • Activiti学习笔记一 工作流基本概念

    最近刚接触流程引擎这一概念 xff0c 对Activiti进行学习 xff0c 感觉正在入门中 xff0c 整理下自己的学习笔记把 xff01 1 xff1a 工作流的概念 工作流 Workflow xff0c 就是 业务过程的部分或整体在
  • Activiti学习笔记六 流程实例 任务 执行对象控制流程执行

    上一篇我们看了流程定义 xff0c 我们接下来看一下流程实例 xff0c 任务 xff0c 和执行对象 流程实例 任务的执行 1 流程图 2 部署流程定义 private final ProcessEngine processEngine
  • datetimepicker 控件验证问题

    34 baseStudents activistTime 34 trigger 39 blur 39 validators notEmpty message 39 确定积极分子时间不能为空 39 span class hljs tag lt
  • eclipse中SVN分支合并到主干

    在项目开发中 xff0c 需要添加一些新的功能 xff0c 但是又不想影响到其他开发人员的项目进度 xff0c 所以决定使用SVN分支进行开发 xff0c 分支开发完毕后再合并到主干 本文介绍如何在eclipse中合并分支到主干 要想将分支
  • 阿里云服务器

    一年多之前 xff0c 也就11年5月份的样子 xff0c 阿里云云服务器产品线终于上线了 但那时候 xff0c 国内完全没有能称得上云服务器的 xff0c 很多小公司就是搞个VPS就叫云服务器了 以至于阿里云云服务器刚出来的时候 xff0

随机推荐

  • 双控机制信息化系统管理平台建设的趋势和必要性

    什么是安全双控体系 xff1f 双控体系即风险分级管控和隐患排查治理双重预防机制 xff0c 目的是对生产经营单位内的所有安全隐患进行系统性的全面排查 xff0c 结合相关安全隐患的危险程度 发生的可能性以及带来的严重后果进行分级别的管控
  • mac 下 使用 iterm2 配置及快键键使用

    mac 下 使用 iterm2 配置及快键键使用 标签 xff08 空格分隔 xff09 xff1a mac 之前介绍过一篇关于mac 下使用和配置 iterm2的blog 今天这篇稍微详细一点介绍 并且搭配 zsh zsh 会单独开一篇博
  • 登录报错后,状态码是401并弹出登录框

    前后端分离的项目 xff0c 登录失败后会弹出一个非前端页面登录框 这是因为登录失败 xff0c 返回的响应表头里添加了WWW Authenticate属性 WWW Authenticate Basic realm 61 34 oauth2
  • 解决secureCRT账号密码正确,无法连接服务器,那大概因为不支持新的密钥交换算法

    连接比较新版本的linux类服务器 xff0c 是否出现下面这些问题 xff1f 或者是openstack新建centos7镜像的时候 xff0c 无法连接新创建的centos7系统 我百度或者谷歌好像都没有找到答案啊 xff0c 所以才写
  • 树莓派SSH连接-SSH服务安装与开机自动启动

    1 SSH连接 SSH连接比Telnet远程桌面连接使用更为安全 xff0c 已经成为行业标准 使用SSH连接树莓派 xff0c 可以对树莓派进行远程控制与编程开发 xff0c 在没有桌面环境的条件下使用SSH连接是非常合适的选择 第2节和
  • 【VSCode Git】stage和stash的区别

    VSCode Git stage和stash的区别 问题来源 用vscode提交变更的文件时 xff0c 会发现2个相似的选项 Stage Changes 和 Stash Changes xff0c 乍一看不知道用哪个 xff0c 它们有什
  • canal文档

    简介 github地址 canal k n l xff0c 译意为水道 管道 沟渠 xff0c 主要用途是基于 MySQL 数据库增量日志解析 xff0c 提供增量数据订阅和消费 canal 工作原理 canal 模拟 MySQL slav
  • 自然拼读与词根词缀简版

    词根词缀 词根词缀重点 1 ab abs 表示远离 或否定 2 ac acr 表示尖 xff0c 酸 xff1b 3 aer aero 表示空气 xff0c 天空 4 am 表示爱 5 ambi ambul 表示周围 xff1b 6 ani
  • MySQL递归查询上下级菜单

    正文 在传统的后台管理系统里面经常会需要展示多级菜单关系 xff0c 今天我们来学一下如何使用一条SQL语句展示多级菜单 现在我们有一张corpinfo单位表 xff0c 里面有一个belong字段指向上级单位 xff0c 首先来看一下现在
  • 基于ESP32双无刷FOC电机的瓦力平衡机器人(2)

    恍恍惚惚中 xff0c 感觉瓦力已经慢慢悠悠的向我走来 xff0c 看了他的孤独 xff0c 感觉自己的也就不算什么了 断断续续搞了差不多两周的时间 xff0c 总算是把这些底层模块都调通了 xff08 虽然还完全看不出任何瓦力的影子 xf
  • 嵌入式 职位描述 职位要求

    来于智联招聘 前程无忧 xff0c 有关工作经验 xff0c 管理经验 xff0c 学历一并删掉 xff0c 只剩职位描述 职位要求 看看自己还缺些什么 嵌入式软件工程师 关专业 xff0c 本科或以上学历 xff1b 2 基础扎实 xff
  • 信道脉冲响应CIR

    博客写作技巧 xff1a 遇到的问题 如何解决问题 需要那种帮助 信道脉冲响应 xff1a CIR 问题 xff1a 场强测量系统需要获取场强和信道信息 xff0c 那么CIR是什么 xff1f 如何利用CIR反映信道特性 xff1f 解决
  • OpenMV数据打包发送以及STM32对数据的解析(串口方式)

    今天尝试了使用Openmv用串口发送数据 xff0c 32接收 xff0c 遇到了一些坑 xff0c 但是最后还是实现了 xff0c 难住我的地方并不是关于传输的代码 xff0c 而是那个板子串口3不知道因为什么原因接收到的数据是错误的 x
  • linux下 c++ 服务器开发(一)

    苦逼的c 43 43 程序员还没找到工作 xff0c 所以顺便开始写服务器练手 对内容不满意不要喷我我是写给自己看的 xff08 把自己犯得错误记下来 xff09 1 我的电脑是win10的 xff0c 所以先去网上下虚拟机 xff0c 我
  • 最优化算法——常见优化算法分类及总结

    之前做特征选择 xff0c 实现过基于群智能算法进行最优化的搜索 xff0c 看过一些群智能优化算法的论文 xff0c 在此做一下总结 最优化问题 在生活或者工作中存在各种各样的最优化问题 xff0c 比如每个企业和个人都要考虑的一个问题
  • 利用手机摄像头采集图片运行ORB-SLAM2

    一 ROS配置安装 二 ORB SLAM2配置安装 可参考前文 ROS仿真环境安装与配置 身在江湖的郭大侠的博客 CSDN博客 三 Android手机摄像头与ROS建立通信 GitHub有个开源的项目 xff0c 可以通过wifi将摄像头捕
  • VINS_FUSION

    VINS FUSIO xff2e 意义 VINS Fusion在VINS Mono的基础上 xff0c 添加了GPS等可以获取全局观测信息的传感器 xff0c 使得VINS可以利用全局信息消除累计误差 xff0c 进而减小闭环依赖 此外 x
  • VINS_FUSION编译运行

    一 ROS安装 见前文 二 ceres安装 GitHub地址 xff1a GitHub ceres solver ceres solver A large scale non linear optimization library 14 0
  • Turtlebot2简单控制

    遥控 遥控前为了让turtlebot接受命令 xff0c 需要启动 roslaunch turtlebot bringup minimal lauch 键盘操作命令 xff1a roslaunch turtlebot teleop keyb
  • turtlebot2利用turtlebot_exploration_3d进行自主建图

    安装octomap ros和rviz插件 sudo apt get install ros indigo octomap 源码安装 xff1a turtlebot exploration 3d 本机为Ubuntu16对应的ros版本为kin