Autonomous Navigation using RTAB-Map's RGBD Odometry

classic Classic list List threaded Threaded
5 messages Options
Reply | Threaded
Open this post in threaded view
|

Autonomous Navigation using RTAB-Map's RGBD Odometry

Drane
Hi Mr Mathieu,
Is it possible to do autonomous navigation using RTAB-Map's RGBD Odometry as the only odometry source?

I've tried to do this using the following commands:

Mapping
roscore

rosrun serial serial

rosrun rosserial_python serial_node.py /dev/ttyUSB0 _baud:=230400

roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true

roslaunch rtabmap_ros rgbd_mapping_kinect2.launch resolution:=qhd rtabmap_args:="--delete_db_on_start" rviz:=true rtabmapviz:=false

rosrun teleop_twist_keyboard teleop_twist_keyboard.py

Navigation
rosrun depthimage_to_laserscan depthimage_to_laserscan image:=/kinect2/qhd/image_depth_rect camera_info:=/camera/camera_info

My robot doesn't have nav_msgs/Odometry and tf, then I'm trying to use the /rtabmap/odom topic:
publish_odom.cpp
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
#include "geometry_msgs/Pose2D.h"
#include "geometry_msgs/Twist.h"
#include "std_msgs/Char.h"
#include "std_msgs/UInt16.h"
#include "angles/angles.h"
#include "iostream"

ros::Publisher pub_velocity;
ros::Timer tim_50hz;

//odometry & gyro
double pos_x,pos_y;
double theta;
double buffer_pos_x, buffer_pos_y, buffer_theta;
double offset_pos_x = 0, offset_pos_y = 0, offset_theta = 0;
double linearposx = 0, linearposy = 0, quatx = 0, quaty = 0, quatz = 0, quatw = 0, vex = 0, vey = 0, vez = 0;

//velocity
double vx = 0,vy = 0,vw = 0;
double buffer_vx = 0, buffer_vy = 0, buffer_vw = 0;
double buffer_vx_new = 0, buffer_vy_new = 0, buffer_vw_new = 0;

void manual_move(int _vx, int _vy, int _vw)
{
    geometry_msgs::Twist msg_velocity;
    msg_velocity.linear.x = vx = _vx;
    msg_velocity.linear.y = vy = _vy;
    msg_velocity.angular.z = vw = _vw;
    pub_velocity.publish(msg_velocity);  
}

void callback_velocity (const geometry_msgs::TwistPtr &msg)
{
    buffer_vx_new = msg->linear.x;
    buffer_vx = buffer_vx_new *40;
    buffer_vy_new = msg->linear.y;
    buffer_vy = buffer_vy_new *40;
    buffer_vw_new = msg->angular.z;
    buffer_vw = buffer_vw_new *40;
}

void callback_odometry (const nav_msgs::Odometry::ConstPtr &msg)
{
   linearposx=msg->pose.pose.position.x;
   linearposy=msg->pose.pose.position.y;
   quatx=msg->pose.pose.orientation.x;
   quaty=msg->pose.pose.orientation.y;
   quatz=msg->pose.pose.orientation.z;
   quatw=msg->pose.pose.orientation.w;
   vex=msg->twist.twist.linear.x;
   vey=msg->twist.twist.linear.y;
   vez=msg->twist.twist.angular.z;
}

void callback_50hz(const ros::TimerEvent &time)
{
    manual_move(buffer_vx,buffer_vy,buffer_vw);
    ROS_INFO("%f", theta);
}

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

  ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
  pub_velocity = n.advertise<geometry_msgs::Twist>("pc2stm_velocity",8);

  tf::TransformBroadcaster odom_broadcaster;

  ros::Subscriber sub_odometry = n.subscribe("/rtabmap/odom", 50,callback_odometry);
  ros::Subscriber sub_velocity = n.subscribe("cmd_vel", 8, callback_velocity);

  tim_50hz = n.createTimer(ros::Duration(0.02), callback_50hz);

  ros::Time current_time, last_time;
  current_time = ros::Time::now();
  last_time = ros::Time::now();

  ros::Rate r(50);
  while(n.ok()){

    ros::spinOnce();               // check for incoming messages
    current_time = ros::Time::now();
    
    //first, we'll publish the transform over tf
    geometry_msgs::TransformStamped odom_trans;
    odom_trans.header.stamp = current_time;
    odom_trans.header.frame_id = "odom";
    odom_trans.child_frame_id = "base_link";

    odom_trans.transform.translation.x = linearposx;
    odom_trans.transform.translation.y = linearposy;
    odom_trans.transform.translation.z = 0.0;
    odom_trans.transform.rotation.x = quatx;
    odom_trans.transform.rotation.y = quaty;
    odom_trans.transform.rotation.z = quatz;
    odom_trans.transform.rotation.w = quatw;

    //send the transform
    odom_broadcaster.sendTransform(odom_trans);

    //next, we'll publish the odometry message over ROS
    nav_msgs::Odometry odom;
    odom.header.stamp = current_time;
    odom.header.frame_id = "odom";

    //set the position
    odom.pose.pose.position.x = linearposx;
    odom.pose.pose.position.y = linearposy;
    odom.pose.pose.position.z = 0.0;
    odom.pose.pose.orientation.x = quatx;
    odom.pose.pose.orientation.y = quaty;
    odom.pose.pose.orientation.z = quatz;
    odom.pose.pose.orientation.w = quatw;

    //set the velocity
    odom.child_frame_id = "base_link";
    odom.twist.twist.linear.x = vex;
    odom.twist.twist.linear.y = vey;
    odom.twist.twist.angular.z = vez;

    //publish the message
    odom_pub.publish(odom);

    last_time = current_time;
    r.sleep();
  }
}

tf_broadcaster.cpp
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>

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

  ros::Rate r(100);

  tf::TransformBroadcaster base_to_laser_broadcaster;

  while(nh.ok()){
    /*base_to_laser_broadcaster.sendTransform(
      tf::StampedTransform(
        tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0, 0, 0)),
        ros::Time::now(),"map", "odom"));*/
    base_to_laser_broadcaster.sendTransform(
      tf::StampedTransform(
        tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0, 0, 0)),
        ros::Time::now(),"odom", "base_link"));
    base_to_laser_broadcaster.sendTransform(
      tf::StampedTransform(
        tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.07, 0.0, 0.64)),
        ros::Time::now(),"base_link", "base_laser"));
    base_to_laser_broadcaster.sendTransform( 
      tf::StampedTransform(
        tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0, 0, 0)),
        ros::Time::now(),"base_laser", "camera_link"));
    base_to_laser_broadcaster.sendTransform( 
      tf::StampedTransform(
        tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0, 0, 0)),
        ros::Time::now(),"camera_link", "kinect2_base_link"));
    r.sleep();
  }
}

move_base.launch (using default parameters in http://wiki.ros.org/navigation/Tutorials/RobotSetup except robot_footprint)
<?xml version="1.0"?>

<launch>
  <master auto="start"/>
  
  <arg name="map_topic" default="/rtabmap/grid_map"/>
  
  <remap from="map" to="$(arg map_topic)"/>

  <!-- Run the map server
    <node name="map_server" pkg="map_server" type="map_server" args="$(find mobile_robot_2dnav)/maps/map.yaml"/> -->

  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find mobile_robot_2dnav)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find mobile_robot_2dnav)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find mobile_robot_2dnav)/param/local_costmap_params.yaml" command="load" />
    <rosparam file="$(find mobile_robot_2dnav)/param/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find mobile_robot_2dnav)/param/base_local_planner_params.yaml" command="load" />
  </node>
</launch>

When I do the mapping process the robot's tf moved according to the robot, but when I run the publish_odom.cpp the robot's tf is not moving correctly, and there are errors relating to the odom's quaternion. I can't set the 2D Pose Estimate in rviz too and when I send the 2D Nav Goal the robot will travel some distance and then keep rotating in place.

So I think the odom is not published correctly or the subscribed topic is wrong? How can I publish RTAB-Map's RGBD Odometry correctly?

Thank You
Reply | Threaded
Open this post in threaded view
|

Re: Autonomous Navigation using RTAB-Map's RGBD Odometry

matlabbe
Administrator
Hi,

For your question yes. See for example the 5. If you don't have the robot section here :http://wiki.ros.org/rtabmap_ros/Tutorials/MappingAndNavigationOnTurtlebot

You don't need to republish /rtabmap/odom, just remap it to /odom. See http://wiki.ros.org/Remapping%20Arguments for more info about remapping.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Autonomous Navigation using RTAB-Map's RGBD Odometry

Drane
Thank you very much for answering my question, should I add these parameters from demo_turtlebot_mapping.launch to rgbd_mapping_kinect2.launch
<!-- Fix odom covariance as in simulation the covariance in /odom topic is high (0.1 for linear and 0.05 for angular) -->
          <param unless="$(arg rgbd_odometry)" name="odom_frame_id" value="odom"/>
          <param unless="$(arg rgbd_odometry)" name="odom_tf_linear_variance" value="0.001"/>
          <param unless="$(arg rgbd_odometry)" name="odom_tf_angular_variance" value="0.001"/>
Reply | Threaded
Open this post in threaded view
|

Re: Autonomous Navigation using RTAB-Map's RGBD Odometry

Drane
In reply to this post by matlabbe
The robot is still spinning in place and I can't set the 2D Pose Estimate & 2D Nav Goal in rviz. Here are the errors:
rgbd_mapping_kinect2.launch
[ERROR] (2019-09-09 03:26:58.794) Rtabmap.cpp:1038::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 8468 is ignored!
[ INFO] [1567974418.794618451]: rtabmap (535): Rate=1.00s, Limit=0.000s, RTAB-Map=0.0001s, Maps update=0.0000s pub=0.0000s (local map=253, WM=253)
[ WARN] (2019-09-09 03:26:58.891) OdometryF2M.cpp:477::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=9) between -1 and 2134"

move_base.launch
[ INFO] [1567974190.948698510]: Using plugin "static_layer"
[ INFO] [1567974190.999688619]: Requesting the map...
[ INFO] [1567974191.219708710]: Resizing costmap to 269 X 282 at 0.050000 m/pix
[ INFO] [1567974191.320486571]: Received a 269 X 282 map at 0.050000 m/pix
[ INFO] [1567974191.341740947]: Using plugin "obstacle_layer"
[ INFO] [1567974191.353381629]:     Subscribed to Topics: laser_scan_sensor
[ INFO] [1567974191.460013407]: Using plugin "inflation_layer"
[ INFO] [1567974191.760341730]: Using plugin "obstacle_layer"
[ INFO] [1567974191.772317035]:     Subscribed to Topics: laser_scan_sensor
[ INFO] [1567974191.839660455]: Using plugin "inflation_layer"
[ INFO] [1567974192.056783403]: Created local_planner base_local_planner/TrajectoryPlannerROS
[ INFO] [1567974192.117986144]: Sim period is set to 0.05
[ INFO] [1567974192.826001591]: Recovery behavior will clear layer obstacles
[ INFO] [1567974323.088857831]: Resizing costmap to 269 X 284 at 0.050000 m/pix
[ WARN] [1567974328.125312477]: MessageFilter [target=map base_laser ]: Dropped 100.00% of messages so far. Please turn the [ros.costmap_2d.message_notifier] rosconsole logger to DEBUG for more information.
[ WARN] [1567974391.656901867]: Clearing costmap to unstuck robot (3.000000m).
[ WARN] [1567974396.706657562]: Rotate recovery behavior started.
[ WARN] [1567974518.091658591]: Costmap2DROS transform timeout. Current time: 1567974518.0916, global_pose stamp: 1567974517.7267, tolerance: 0.3000
[ WARN] [1567974518.113011973]: Could not get robot pose, cancelling reconfiguration
[ERROR] [1567974672.891736238]: Extrapolation Error looking up robot pose: Lookup would require extrapolation into the past.  Requested time 1567974517.726727406 but the earliest data is at time 1567974662.897800108, when looking up transform from frame [base_link] to frame [map]

rviz rviz
[ WARN] [1567974386.640982387]: MessageFilter [target=map ]: Discarding message from [/move_base] due to empty frame_id.  This message will only print once.
[ WARN] [1567974386.641653553]: Invalid argument passed to canTransform argument source_frame in tf2 frame_ids cannot be empty

Here is the tf frames:
tf frames

Here is the rqt graph:
rqt graph
Reply | Threaded
Open this post in threaded view
|

Re: Autonomous Navigation using RTAB-Map's RGBD Odometry

matlabbe
Administrator
Hi,

For your previous post, if you use /rtabmap/odom, you don't need to set odom_frame_id parameter.

In the tf tree, odom -> base_link should not be published by tf_robot. Note also that you don't need to create a node to publish static tf, just launch multiple instances of static_transform_publisher node.

I updated recently the tutorial with a turtlebot3 example. I suggest to take a look to see how navigation should work.

cheers,
Mathieu