解决roslaunch启动stage_ros节点仿真时输出rostopic hz速率较低的问题(始终为10Hz)

问题描述:

在实验过程中偶然间发现无论是odom还是laser_scan的输出频率都只有10Hz; /clock输出速率有50Hz; 

直接使用命令 rosrun stage_ros stageros test.world能够正常输出50Hz;

最初分析原因可能是处理数据太慢或者CPU被占用,导致数据更新缓慢;

查询输出topic速率的指令如下:

<<< rostopic list
/clock
/rosout
/rosout_agg
/stage/irat/cmd_vel
/stage/irat/odometry
/stage/irat/pose_ground_truth
/stage/irat/ranger_0/laserscan
/tf
<<< rostopic hz /stage/irat/odometry
subscribed to [/stage/irat/odometry]
average rate: 9.988
        min: 0.083s max: 0.122s std dev: 0.01182s window: 9
average rate: 9.999
        min: 0.083s max: 0.122s std dev: 0.01040s window: 19
average rate: 9.978
        min: 0.080s max: 0.124s std dev: 0.01185s window: 29
average rate: 9.997
        min: 0.080s max: 0.124s std dev: 0.01185s window: 39
<<< rostopic hz /stage/irat/ranger_0/laserscan
subscribed to [/stage/irat/ranger_0/laserscan]
average rate: 9.929
        min: 0.090s max: 0.115s std dev: 0.00957s window: 9
average rate: 10.001
        min: 0.086s max: 0.115s std dev: 0.00869s window: 19
average rate: 10.031
        min: 0.086s max: 0.116s std dev: 0.00851s window: 30
<<< rostopic hz /clock
subscribed to [/clock]
average rate: 50.572
        min: 0.010s max: 0.031s std dev: 0.00836s window: 48
average rate: 50.285
        min: 0.009s max: 0.031s std dev: 0.00830s window: 98
average rate: 50.180
        min: 0.008s max: 0.031s std dev: 0.00833s window: 148

查询stage ros在线库,查找有关资料:http://rtv.github.io/Stage/modules.html

尝试一下参数:

#interval_real 20
#show_clock  1
#show_clock_interval 20
#update_interval 20

均没有效果!

只有在position 和 ranger中增加 update_interval 20 才有效!因为update_interval 默认值是100ms,即10Hz

最终的test.world文件

define floorplan model
(
  # sombre, sensible, artistic
  color "gray30"

  # most maps will need a bounding box
  boundary 1
  #update_interval 20

  gui_nose 0
  gui_grid 0
  gui_outline 0
  gui_move 0
  gripper_return 0
  fiducial_return 0
  ranger_return 1
)
resolution 0.02
interval_sim 20  # simulation timestep in milliseconds
#interval_real 20
#show_clock  1
#show_clock_interval 20

# configure the GUI window
window
(
  size [ 600.000 600.000 ] # in pixels
  scale 25 # pixels per meter
  center [ 0.0  0.0 ]
  rotate [ 0.0  0.0 ]  			
  show_data 0 #1=on 0=off
)


# load an environment bitmap
floorplan
(
  name "irat-stage"
  bitmap "bitmaps/hospital_section.png"
  size [ 108.6 43.3 2.0 ]
  pose [ 0.0 0.0 0.0 0.0]
)

define laser ranger
(

  # generic model properties
  color "blue"
  size [ 0.156 0.155 0.19 ]
  update_interval 20
  sensor
  (
    range [0.0 8.0]
    fov 360.0
    samples 360    
    noise [ 0 0.01 0.01 ]
  )
)

define robot position
(
  size [ 0.33 0.33 0.2 ]
  #pose [ 0.0 0.0 0.0 0.0 ]  
  localization "gps"
  localization_origin [ 0.0 0.0 0.0 0.0 ]
  update_interval 20

  # odometry error model parameters, 
  # only used if localization is set to "odom"
  odom_error [ 0.0 0.0 0.0 0.0 ]
  #color "gray50"
  origin [ 0.0 0.0 0.0 0.0 ]
  #positonal things
  drive "diff"
  gui_nose 1
  laser(
        pose [ 0.0 0.0 0.5 0.0 ] 
	#ctrl "lasernoise" 
	alwayson 1	
	)

)
robot
(
 name "irat"
 pose [-17 8 0.0 0.0] 
 color "green"
 #ctrl "wander"
)

本系统为ros melodic, stage 版本 4.3

最终效果:

<<< rostopic hz /stage/irat/ranger_0/laserscan
subscribed to [/stage/irat/ranger_0/laserscan]
average rate: 50.487
        min: 0.001s max: 0.046s std dev: 0.01113s window: 48
average rate: 50.039
        min: 0.001s max: 0.047s std dev: 0.01061s window: 98
average rate: 50.066
        min: 0.001s max: 0.047s std dev: 0.01024s window: 148
<<< rostopic hz /stage/irat/odometry
subscribed to [/stage/irat/odometry]
average rate: 50.881
        min: 0.001s max: 0.044s std dev: 0.01059s window: 48

 

  • 1
    点赞
  • 6
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值