move_base_legacy_relay.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # @author Jorge Santos
4 # License: 3-Clause BSD
5 
6 import actionlib
7 import copy
8 
9 import rospy
10 import nav_msgs.srv as nav_srvs
11 import mbf_msgs.msg as mbf_msgs
12 import move_base_msgs.msg as mb_msgs
13 from dynamic_reconfigure.client import Client
14 from dynamic_reconfigure.server import Server
15 from geometry_msgs.msg import PoseStamped
16 from move_base.cfg import MoveBaseConfig
17 
18 
19 """
20 move_base legacy relay node:
21 Relays old move_base actions to the new mbf move_base action, similar but with richer result and feedback.
22 We also relay the simple goal topic published by RViz, the make_plan service and dynamic reconfiguration
23 calls (note that some parameters have changed names; see http://wiki.ros.org/move_base_flex for details)
24 """
25 
26 
27 def simple_goal_cb(msg):
28  mbf_mb_ac.send_goal(mbf_msgs.MoveBaseGoal(target_pose=msg))
29  rospy.logdebug("Relaying move_base_simple/goal pose to mbf")
30 
31 
32 def mb_execute_cb(msg):
33  mbf_mb_ac.send_goal(mbf_msgs.MoveBaseGoal(target_pose=msg.target_pose), feedback_cb=mbf_feedback_cb)
34  rospy.logdebug("Relaying legacy move_base goal to mbf")
35  mbf_mb_ac.wait_for_result()
36 
37  status = mbf_mb_ac.get_state()
38  result = mbf_mb_ac.get_result()
39 
40  rospy.logdebug("MBF execution completed with result [%d]: %s", result.outcome, result.message)
41  if result.outcome == mbf_msgs.MoveBaseResult.SUCCESS:
42  mb_as.set_succeeded(mb_msgs.MoveBaseResult(), "Goal reached.")
43  else:
44  mb_as.set_aborted(mb_msgs.MoveBaseResult(), result.message)
45 
46 
47 def make_plan_cb(request):
48  mbf_gp_ac.send_goal(mbf_msgs.GetPathGoal(start_pose=request.start, target_pose=request.goal,
49  use_start_pose = bool(request.start.header.frame_id),
50  tolerance=request.tolerance))
51  rospy.logdebug("Relaying legacy make_plan service to mbf get_path action server")
52  mbf_gp_ac.wait_for_result()
53 
54  status = mbf_gp_ac.get_state()
55  result = mbf_gp_ac.get_result()
56 
57  rospy.logdebug("MBF get_path execution completed with result [%d]: %s", result.outcome, result.message)
58  if result.outcome == mbf_msgs.GetPathResult.SUCCESS:
59  return nav_srvs.GetPlanResponse(plan=result.path)
60 
61 
62 def mbf_feedback_cb(feedback):
63  mb_as.publish_feedback(mb_msgs.MoveBaseFeedback(base_position=feedback.current_pose))
64 
65 
66 def mb_reconf_cb(config, level):
67  rospy.logdebug("Relaying legacy move_base reconfigure request to mbf")
68 
69  if not hasattr(mb_reconf_cb, "default_config"):
70  mb_reconf_cb.default_config = copy.deepcopy(config)
71 
72  if config.get('restore_defaults'):
73  config = mb_reconf_cb.default_config
74 
75  mbf_config = copy.deepcopy(config)
76 
77  # Map move_base legacy parameters to new mbf ones
78  if 'base_local_planner' in mbf_config: # mbf doesn't allow changing plugins dynamically
79  mbf_config.pop('base_local_planner')
80  if 'controller_frequency' in mbf_config:
81  mbf_config['controller_frequency'] = mbf_config.pop('controller_frequency')
82  if 'controller_patience' in mbf_config:
83  mbf_config['controller_patience'] = mbf_config.pop('controller_patience')
84  if 'max_controller_retries' in mbf_config:
85  mbf_config['controller_max_retries'] = mbf_config.pop('max_controller_retries')
86  if 'base_global_planner' in mbf_config:
87  mbf_config.pop('base_global_planner') # mbf doesn't allow changing plugins dynamically
88  if 'planner_frequency' in mbf_config:
89  mbf_config['planner_frequency'] = mbf_config.pop('planner_frequency')
90  if 'planner_patience' in mbf_config:
91  mbf_config['planner_patience'] = mbf_config.pop('planner_patience')
92  if 'max_planning_retries' in mbf_config:
93  mbf_config['planner_max_retries'] = mbf_config.pop('max_planning_retries')
94  if 'recovery_behavior_enabled' in mbf_config:
95  mbf_config['recovery_enabled'] = mbf_config.pop('recovery_behavior_enabled')
96  if 'conservative_reset_dist' in mbf_config:
97  mbf_config.pop('conservative_reset_dist') # no mbf equivalent for this!
98  if 'clearing_rotation_allowed' in mbf_config:
99  mbf_config.pop('clearing_rotation_allowed') # no mbf equivalent for this! TODO: shouldn't? don't think so... if you don't want rotation, do not include that behavior! on recovery_behaviors list!
100  # Btw, recovery_behaviors is commented out on MoveBase.cfg, so it doesn't apear here
101  mbf_drc.update_configuration(mbf_config)
102  return config
103 
104 
105 if __name__ == '__main__':
106  rospy.init_node("move_base")
107 
108  # TODO what happens with malformed target goal??? FAILURE or INVALID_POSE
109  # txt must be: "Aborting on goal because it was sent with an invalid quaternion"
110 
111  # move_base_flex get_path and move_base action clients
112  mbf_mb_ac = actionlib.SimpleActionClient("move_base_flex/move_base", mbf_msgs.MoveBaseAction)
113  mbf_gp_ac = actionlib.SimpleActionClient("move_base_flex/get_path", mbf_msgs.GetPathAction)
114  mbf_mb_ac.wait_for_server(rospy.Duration(20))
115  mbf_gp_ac.wait_for_server(rospy.Duration(10))
116 
117  # move_base_flex dynamic reconfigure client
118  mbf_drc = Client("move_base_flex", timeout=10)
119 
120  # move_base simple topic and action server
121  mb_sg = rospy.Subscriber('move_base_simple/goal', PoseStamped, simple_goal_cb)
122  mb_as = actionlib.SimpleActionServer('move_base', mb_msgs.MoveBaseAction, mb_execute_cb, auto_start=False)
123  mb_as.start()
124 
125  # move_base make_plan service
126  mb_mps = rospy.Service('~make_plan', nav_srvs.GetPlan, make_plan_cb)
127 
128  # move_base dynamic reconfigure server
129  mb_drs = Server(MoveBaseConfig, mb_reconf_cb)
130 
131  rospy.spin()
def mb_reconf_cb(config, level)


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:40