Skip to content

Commit 67a7458

Browse files
authored
Merge pull request #1147 from knorth55/fetch-fix-nav
fix fetch robot localization and navigation (graft vs robot_localization is still under discussion; fetchrobotics/fetch_robots#56 )
2 parents 8e5d37c + 8d279ca commit 67a7458

6 files changed

Lines changed: 180 additions & 30 deletions

File tree

jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch

Lines changed: 97 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -137,39 +137,113 @@
137137
<arg name="map_keepout_file" value="$(arg keepout_map_file)" />
138138
<arg name="use_keepout" value="true" />
139139
</include>
140+
141+
<!-- robot localization ukf -->
142+
<node pkg="robot_localization" type="ukf_localization_node" name="ukf_se" clear_params="true">
143+
<remap from="odometry/filtered" to="/odom_combined" />
144+
<rosparam>
145+
frequency: 50
146+
sensor_timeout: 1.0
147+
two_d_mode: true
148+
publish_tf: true
149+
publish_acceleration: false
150+
map_frame: map
151+
odom_frame: odom
152+
base_link_frame: base_link
153+
odom0: /odom_corrected
154+
odom0_config: [true, true, false,
155+
false, false, true,
156+
true, true, false,
157+
false, false, true,
158+
false, false, false]
159+
odom0_nodelay: true
160+
odom0_differential: true
161+
imu0: /imu_corrected
162+
imu0_config: [false, false, false,
163+
false, false, false,
164+
false, false, false,
165+
false, false, true,
166+
true, true, false]
167+
imu0_nodelay: true
168+
imu0_differential: true
169+
imu0_remove_gravitational_acceleration: true
170+
</rosparam>
171+
</node>
172+
140173
<rosparam ns="amcl">
141174
update_min_a: 0.01 <!-- update filter every 0.01[m] translation -->
142175
update_min_d: 0.01 <!-- update filter every 0.01[rad] rotation -->
176+
odom_alpha1: 0.2 # rotation noise per rotation
177+
odom_alpha2: 0.2 # rotation noise per translation
178+
odom_alpha3: 0.2 # translation noise per translation
179+
odom_alpha4: 0.2 # translation noise per rotation
180+
</rosparam>
181+
182+
<rosparam ns="move_base">
183+
controller_frequency: 10.0
143184
</rosparam>
144185

145186
<rosparam ns="move_base/global_costmap">
146-
inflater:
147-
inflation_radius: 0.30 # 0.7
148-
cost_scaling_factor: 10.0 # 10.0
187+
inflater:
188+
inflation_radius: 0.7 # 0.7
189+
cost_scaling_factor: 5.0 # 10.0
190+
obstacles:
191+
min_obstacle_height: 0.05
192+
footprint_padding: 0.05
149193
</rosparam>
150194
<rosparam ns="move_base/local_costmap">
151-
inflater:
152-
inflation_radius: 0.30 # 0.7
153-
cost_scaling_factor: 100.0 # 25.0 default 10, increasing factor decrease the cost value
154-
update_frequency: 10.0 # default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
195+
inflater:
196+
inflation_radius: 0.7 # 0.7
197+
cost_scaling_factor: 5.0 # 25.0 default 10, increasing factor decrease the cost value
198+
obstacles:
199+
min_obstacle_height: 0.05
200+
# default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
201+
update_frequency: 10.0
202+
footprint_padding: 0.05
155203
</rosparam>
156204
<rosparam ns="move_base">
157-
base_local_planner: base_local_planner/TrajectoryPlannerROS
158-
TrajectoryPlannerROS:
159-
escape_vel: -0.1 # -0.1
160-
recovery_behavior_enabled: true
161-
recovery_behaviors:
162-
- name: "conservative_reset"
163-
type: "clear_costmap_recovery/ClearCostmapRecovery"
164-
- name: "rotate_recovery"
165-
type: "rotate_recovery/RotateRecovery"
166-
frequency: 20.0
167-
sim_granularity: 0.017
168-
- name: "aggressive_reset"
169-
type: "clear_costmap_recovery/ClearCostmapRecovery"
170-
conservative_reset: {reset_distance: 1.0} # 3.0
171-
aggressive_reset: {reset_distance: 0.2} # 0.5
172-
move_slow_and_clear: {clearing_distance: 0.5, limited_distance: 0.3, limited_rot_speed: 0.45, limited_trans_speed: 0.25}
205+
base_local_planner: base_local_planner/TrajectoryPlannerROS
206+
TrajectoryPlannerROS:
207+
min_in_place_vel_theta: 1.0
208+
escape_vel: -0.1 # -0.1
209+
vx_samples: 10
210+
meter_scoring: true
211+
pdist_scale: 5.0
212+
gdist_scale: 3.2
213+
occdist_scale: 0.1
214+
dwa: true
215+
recovery_behavior_enabled: true
216+
recovery_behaviors:
217+
- name: "conservative_reset"
218+
type: "clear_costmap_recovery/ClearCostmapRecovery"
219+
- name: "rotate_recovery"
220+
type: "rotate_recovery/RotateRecovery"
221+
frequency: 20.0
222+
sim_granularity: 0.017
223+
- name: "aggressive_reset"
224+
type: "clear_costmap_recovery/ClearCostmapRecovery"
225+
conservative_reset:
226+
reset_distance: 1.0 # 3.0
227+
aggressive_reset:
228+
reset_distance: 0.2 # 0.5
229+
move_slow_and_clear:
230+
clearing_distance: 0.5
231+
limited_distance: 0.3
232+
limited_rot_speed: 0.45
233+
limited_trans_speed: 0.25
173234
</rosparam>
174235
</group>
236+
237+
<!-- /imu has no frame_id information and there is no bug fix release in indigo. -->
238+
<!-- see https://github.com/fetchrobotics/fetch_ros/issues/70 -->
239+
<node name="imu_corrector" pkg="jsk_fetch_startup" type="imu_corrector.py">
240+
<remap from="~input" to="/imu" />
241+
<remap from="~output" to="/imu_corrected" />
242+
</node>
243+
244+
<!-- /odom has no covariance value. -->
245+
<node name="odom_corrector" pkg="jsk_fetch_startup" type="odom_corrector.py">
246+
<remap from="~input" to="/odom" />
247+
<remap from="~output" to="/odom_corrected" />
248+
</node>
175249
</launch>

jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,16 @@
7777
<rosparam file="$(find fetch_navigation)/config/costmap_local.yaml" command="load" ns="local_costmap" />
7878
<rosparam file="$(find fetch_navigation)/config/fetch/costmap_local.yaml" command="load" ns="local_costmap" />
7979
</node>
80+
<rosparam ns="safe_teleop_base/local_costmap">
81+
inflater:
82+
inflation_radius: 1.0 # 0.7
83+
cost_scaling_factor: 3.0 # 25.0 default 10, increasing factor decrease the cost value
84+
obstacles:
85+
min_obstacle_height: 0.05
86+
# default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
87+
update_frequency: 10.0
88+
footprint_padding: 0.05
89+
</rosparam>
8090

8191
<node name="safe_tilt_head" pkg="jsk_fetch_startup" type="safe_tilt_head.py" />
8292

jsk_fetch_robot/jsk_fetch_startup/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
<run_depend>amcl</run_depend>
2929
<run_depend>map_server</run_depend>
3030
<run_depend>move_base</run_depend>
31+
<run_depend>robot_localization</run_depend>
3132

3233
<!-- for fetch teleop -->
3334
<run_depend>app_manager</run_depend>

jsk_fetch_robot/jsk_fetch_startup/scripts/correct_position.py

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -22,24 +22,31 @@ def __init__(self):
2222
self.dock_pose = spot.pose
2323

2424
self.is_docking = False
25+
self.timer = rospy.Timer(rospy.Duration(1.0), self._cb_correct_position)
2526

2627
def subscribe(self):
27-
self.sub_dock = rospy.Subscriber('/battery_state',
28-
BatteryState,
29-
self._cb_correct_position)
28+
self.sub_dock = rospy.Subscriber(
29+
'/battery_state', BatteryState, self._cb)
3030

3131
def unsubscribe(self):
3232
self.sub_dock.unregister()
3333

34-
def _cb_correct_position(self, msg):
35-
if msg.is_charging and (not self.is_docking):
34+
def _cb(self, msg):
35+
self.is_docking = msg.is_charging
36+
37+
def _cb_correct_position(self, event):
38+
if self.is_docking:
3639
self.pos = PoseWithCovarianceStamped()
3740
self.pos.header.stamp = rospy.Time.now()
3841
self.pos.header.frame_id = 'map'
3942
self.pos.pose.pose = self.dock_pose
40-
self.pos.pose.covariance = [0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891945200942]
43+
self.pos.pose.covariance = [1e-3, 0.0, 0.0, 0.0, 0.0, 0.0,
44+
0.0, 1e-3, 0.0, 0.0, 0.0, 0.0,
45+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
46+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
47+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
48+
0.0, 0.0, 0.0, 0.0, 0.0, 1e-3]
4149
self.pub.publish(self.pos)
42-
self.is_docking = msg.is_charging
4350

4451

4552
if __name__ == '__main__':
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
#!/usr/bin/env python
2+
3+
import rospy
4+
5+
from sensor_msgs.msg import Imu
6+
7+
8+
class ImuCorrector(object):
9+
def __init__(self):
10+
super(ImuCorrector, self).__init__()
11+
self.sub = rospy.Subscriber(
12+
'~input', Imu, self._cb, queue_size=1)
13+
self.pub = rospy.Publisher(
14+
'~output', Imu, queue_size=1)
15+
16+
def _cb(self, msg):
17+
msg.header.frame_id = 'base_link'
18+
msg.angular_velocity_covariance = [0, 0, 0,
19+
0, 0, 0,
20+
0, 0, 4e-6]
21+
self.pub.publish(msg)
22+
23+
24+
if __name__ == '__main__':
25+
rospy.init_node('imu_corrector')
26+
app = ImuCorrector()
27+
rospy.spin()
Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
#!/usr/bin/env python
2+
3+
import rospy
4+
5+
from nav_msgs.msg import Odometry
6+
7+
8+
class OdomCorrector(object):
9+
def __init__(self):
10+
super(OdomCorrector, self).__init__()
11+
self.sub = rospy.Subscriber(
12+
'~input', Odometry, self._cb, queue_size=1)
13+
self.pub = rospy.Publisher(
14+
'~output', Odometry, queue_size=1)
15+
self.covariance = [1e-3, 0, 0, 0, 0, 0,
16+
0, 1e-3, 0, 0, 0, 0,
17+
0, 0, 0, 0, 0, 0,
18+
0, 0, 0, 0, 0, 0,
19+
0, 0, 0, 0, 0, 0,
20+
0, 0, 0, 0, 0, 1e-3]
21+
22+
def _cb(self, msg):
23+
msg.pose.covariance = self.covariance
24+
msg.twist.covariance = self.covariance
25+
self.pub.publish(msg)
26+
27+
28+
if __name__ == '__main__':
29+
rospy.init_node('odom_corrector')
30+
app = OdomCorrector()
31+
rospy.spin()

0 commit comments

Comments
 (0)