Strange behavior between move_base Navigation Stack and Rviz
This is my graduation project from college and I can't figure out the problem. I have an environment build specifically for this project and build a map of it with hector SLAM. The goal is for the Mobile robot moving around the static map for specific goal set by Rviz.
UPDATE THE OLD 2 BEHAVIORS ARE NOT HAPPENING ANYMORE: I ADJUSTED LINOROBOT COSTMAPS TO WORK FOR ME AND IT FIXED THOSE 2 ERRORS. HOWEVER, THIS SOLUTION INTRODUCED:
DWA planner failed to produce path
Off Map 1.098, -0.050
Old behaviors:
Rviz behavior Video: Google drive Rviz localization video
Rviz behavior when trying to estimate pose: Google drive estimate pose behavior NOTE: the robot was not in the designed environment when taking this video, this video is just for demonstration
The errors I'm getting: UPDATED
roswtf:
WARNING The following node subscriptions are unconnected:
* /amcl:
* /tf_static
* /rviz_1542954558890249147:
* /move_base/TrajectoryPlannerROS/global_plan
* /move_base/NavfnROS/plan
* /tf_static
* /map_updates
* /move_base/TrajectoryPlannerROS/local_plan
* /rqt_gui_py_node_27505:
* /statistics
* /move_base:
* /tf_static
* /move_base/cancel
WARNING Received out-of-date/future transforms:
* receiving transform from [/amcl] that differed from ROS time by 1.176933497s
Found 1 error(s).
ERROR The following nodes should be connected but aren't:
* /move_base->/move_base (/move_base/global_costmap/footprint)
* /move_base->/move_base (/move_base/local_costmap/footprint)
AMCL warning: [ WARN] [1542907954.448988739]: Frameid of map received:'/odom' doesn't match globalframe_id:'map'. This could cause issues with reading published topics
FIXED BY MAKING MAP_SERVER FRAME ID TO BE MAP
Rviz Global option's fixed frame: map
FIXED BY THE COSTMAP CONFIG
Blockquote TF configuration: Tree --> odom --> base_link --> laser --> mapcurrent
updated
TF configuration: map-->odom-->base_link-->laserrqt_graph: rqt graph picture
Packages used:
- Rplidar (for the lidar I have)
- motor_hat (for the motor control)
- robotsetuptf (for publishing the tf information)
- robotdrive (for publishing commands for the motorhat)
- differential_drive (for publishing odom, twist commands and the PID controller)
- move_base (costmaps)
- amcl (for localization)
- map_server (to publish the map)
robot launch file:
<launch>
<rosparam param="ticks_meter">6000</rosparam>
<include file="$(find rplidar_ros)/launch/rplidar.launch"/>
<node pkg="robot_setup_wheelencoders" type="rwheel.py" name="rwheel"/>
<node pkg="robot_setup_wheelencoders" type="lwheel.py" name="lwheel"/>
<node pkg="differential_drive" type="diff_tf.py" name="diff_tf" output="screen">
<rosparam param="rate">8.0</rosparam>
<rosparam param="base_width">0.294</rosparam>
</node>
<node pkg="robot_setup_tf" type="tf_broadcaster" name="tf_broadcaster"/>
<node pkg="motor_hat" type="motor_hat_node" name="driving"/>
<node pkg="robot_drive" type="robot_drive.py" name="drive_cmd"/>
<node pkg="differential_drive" type="twist_to_motors.py" name="twist_to_motors" output="screen">
<rosparam param="base_width">0.294</rosparam>
</node>
<node pkg="differential_drive" type="pid_velocity.py" name="lpid_velocity">
<remap from="wheel" to="lwheel"/>
<remap from="motor_cmd" to="lmotor_cmd"/>
<remap from="wheel_vtarget" to="lwheel_vtarget"/>
<remap from="wheel_vel" to="lwheel_vel"/>
<rosparam param="Kp">75</rosparam>
<rosparam param="Ki">148</rosparam>
<rosparam param="Kd">0</rosparam>
<rosparam param="out_min">-255</rosparam>
<rosparam param="out_max">255</rosparam>
<rosparam param="rate">30</rosparam>
<rosparam param="timeout_ticks">4</rosparam>
<rosparam param="rolling_pts">5</rosparam>
</node>
<node pkg="differential_drive" type="pid_velocity.py" name="rpid_velocity">
<remap from="wheel" to="rwheel"/>
<remap from="motor_cmd" to="rmotor_cmd"/>
<remap from="wheel_vtarget" to="rwheel_vtarget"/>
<remap from="wheel_vel" to="rwheel_vel"/>
<rosparam param="Kp">75</rosparam>
<rosparam param="Ki">148</rosparam>
<rosparam param="Kd">0</rosparam>
<rosparam param="out_min">-255</rosparam>
<rosparam param="out_max">255</rosparam>
<rosparam param="rate">30</rosparam>
<rosparam param="timeout_ticks">4</rosparam>
<rosparam param="rolling_pts">5</rosparam>
</node>
<include file="$(find AVSrobot)/launch/move_base.launch"/>
</launch>
move_base launch file:
<launch>
<!-- Run the map server -->
<arg name="map_file" default="$(find AVSrobot)/maps/demotest11194.yaml"/>
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" respawn="false">
<param name="frame_id" value="/odom" />
</node>
<!--- Run AMCL -->
<include file="$(find amcl)/examples/amcl_AVS.launch" />
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find AVSrobot)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find AVSrobot)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find AVSrobot)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find AVSrobot)/config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find AVSrobot)/config/base_local_planner_params.yaml" command="load" />
</node>
</launch>
robotsetuptf:
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
int main(int argc, char** argv)
{
ros::init(argc, argv, "robot_tf_publisher");
ros::NodeHandle n;
ros::Rate r(100);
tf::TransformBroadcaster broadcaster;
while(n.ok()){
//broadcaster.sendTransform(
//tf::StampedTransform(
//tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.0, 0.0, 0.0)),
//ros::Time::now(), "map", "odom"));
broadcaster.sendTransform(
tf::StampedTransform(
tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.0, 0.0, 0.2)),
ros::Time::now(),"base_link", "laser"));
r.sleep();
}
}
Costmaps:
baselocalplanner_params.yaml:
TrajectoryPlannerROS:
max_vel_x: 0.45
min_vel_x: 0.1
max_vel_theta: 1.0
min_vel_theta: -1.0
min_in_place_vel_theta: 0.4
escape_vel: -0.1
acc_lim_theta: 3.2
acc_lim_x: 2.5
acc_lim_y: 2.5
holonomic_robot: false
yaw_goal_tolerance: 0.05
xy_goal_tolerance: 0.10
latch_xy_goal_tolerance: false
sim_time: 2
sim_granularity: 0.10
angular_sim_granularity: 0.10
vx_samples: 3
vtheta_samples: 20
meter_scoring: true
pdist_scale: 0.6
gdist_scale: 1.0
occdist_scale: 0.1
heading_lookahead: 0.325
heading_scoring: false
dwa: true
global_frame_id: odom
oscillation_reset_dist: 0.30
prune_plan: true
costmapcommonparams.yaml:
footprint: [[-0.15,-0.15],[-0.15,0.15], [0.15, 0.15], [0.15,-0.15]]
obstacle_range: 2.0
raytrace_range: 2.5
inflation_radius: 0.3
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}
globalcostmapparams.yaml:
global_costmap:
global_frame: map
robot_base_frame: base_link
update_frequency: 5.0
static_map: true
transform_tolerance: 0.5
localcostmapparams.yaml:
local_costmap:
global_frame: odom
robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
rolling_window: true
width: 2.0
height: 2.0
resolution: 0.05
transform_tolerance: 0.5
amcl configuration launch file:
<launch>
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<!-- Publish scans from best pose at a max of 10 Hz -->
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha5" value="0.1"/>
<param name="transform_tolerance" value="0.2" />
<param name="gui_publish_rate" value="10.0"/>
<param name="laser_max_beams" value="90"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="5000"/>
<param name="kld_err" value="0.05"/>
<param name="kld_z" value="0.99"/>
<param name="odom_alpha1" value="0.2"/>
<param name="odom_alpha2" value="0.2"/>
<!-- translation std dev, m -->
<param name="odom_alpha3" value="0.8"/>
<param name="odom_alpha4" value="0.2"/>
<param name="laser_z_hit" value="0.5"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.5"/>
<param name="laser_min_range" value="0.15"/>
<param name="laser_max_range" value="0.4"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_model_type" value="likelihood_field"/>
<!-- <param name="laser_model_type" value="beam"/> -->
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d" value="0.2"/>
<param name="update_min_a" value="0.5"/>
<param name="odom_frame_id" value="odom"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.1"/>
<param name="recovery_alpha_slow" value="0.001"/>
<param name="recovery_alpha_fast" value="0.1"/>
</node>
</launch>
Asked by karimemara17 on 2018-11-22 13:00:12 UTC
Comments
Here's a bag file to of the project too Google drive bag file link
Asked by karimemara17 on 2018-11-22 14:15:51 UTC
I don't see you odom-->base_link transform. Is that in there somewhere? Also, TF configuration: Tree --> odom --> base_link --> laser --> map is incorrect if that is really is how it is set up. Run rosrun tf view_frames to get view. Should be map-->odom-->base_link-->laser. What is "Tree"?
Asked by billy on 2018-11-22 16:55:25 UTC
I fixed the tree to what you suggested yes now it is "map-->odom-->base_link-->laser" I think amcl from the Navigation Stack provide the transform from odom to base_link, right?
I'm working on it now and after fixing the tree, a new error for the the local_costmap it says it doesn't have a map!
Asked by karimemara17 on 2018-11-22 17:31:04 UTC
The frame pdf generated by rosrun tf view frame
Asked by karimemara17 on 2018-11-22 20:06:56 UTC
Your frame.pdf shows odom-->base_link is coming from the diff node I didn't see above. AMCL is publishing the map --> odom TF so you've got a lot working. Can you see the map in RVIZ? Update your question with new error.
Asked by billy on 2018-11-23 00:36:42 UTC
Is it okay that the frames are coming from the diff node and the AMCL? I will update it right now. UPDATED. should I close this question and start a new one? and Billy do you mind sharing contact information if you are welling to help me get this to work? the problems are path and driving
Asked by karimemara17 on 2018-11-23 01:22:28 UTC
Me providing contact information would require I get named credit on the Project Cover page. Better to keep it public to help others with similar questions.
Current error of "off map" seems intuitive. How did you set initial pose and goal?
Asked by billy on 2018-11-23 16:51:16 UTC