diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 8a2c7660a5..30e29fd74f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -137,39 +137,113 @@ + + + + + + frequency: 50 + sensor_timeout: 1.0 + two_d_mode: true + publish_tf: true + publish_acceleration: false + map_frame: map + odom_frame: odom + base_link_frame: base_link + odom0: /odom_corrected + odom0_config: [true, true, false, + false, false, true, + true, true, false, + false, false, true, + false, false, false] + odom0_nodelay: true + odom0_differential: true + imu0: /imu_corrected + imu0_config: [false, false, false, + false, false, false, + false, false, false, + false, false, true, + true, true, false] + imu0_nodelay: true + imu0_differential: true + imu0_remove_gravitational_acceleration: true + + + update_min_a: 0.01 update_min_d: 0.01 + odom_alpha1: 0.2 # rotation noise per rotation + odom_alpha2: 0.2 # rotation noise per translation + odom_alpha3: 0.2 # translation noise per translation + odom_alpha4: 0.2 # translation noise per rotation + + + + controller_frequency: 10.0 -inflater: - inflation_radius: 0.30 # 0.7 - cost_scaling_factor: 10.0 # 10.0 + inflater: + inflation_radius: 0.7 # 0.7 + cost_scaling_factor: 5.0 # 10.0 + obstacles: + min_obstacle_height: 0.05 + footprint_padding: 0.05 -inflater: - inflation_radius: 0.30 # 0.7 - cost_scaling_factor: 100.0 # 25.0 default 10, increasing factor decrease the cost value -update_frequency: 10.0 # default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide) + inflater: + inflation_radius: 0.7 # 0.7 + cost_scaling_factor: 5.0 # 25.0 default 10, increasing factor decrease the cost value + obstacles: + min_obstacle_height: 0.05 + # default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide) + update_frequency: 10.0 + footprint_padding: 0.05 -base_local_planner: base_local_planner/TrajectoryPlannerROS -TrajectoryPlannerROS: - escape_vel: -0.1 # -0.1 -recovery_behavior_enabled: true -recovery_behaviors: - - name: "conservative_reset" - type: "clear_costmap_recovery/ClearCostmapRecovery" - - name: "rotate_recovery" - type: "rotate_recovery/RotateRecovery" - frequency: 20.0 - sim_granularity: 0.017 - - name: "aggressive_reset" - type: "clear_costmap_recovery/ClearCostmapRecovery" -conservative_reset: {reset_distance: 1.0} # 3.0 -aggressive_reset: {reset_distance: 0.2} # 0.5 -move_slow_and_clear: {clearing_distance: 0.5, limited_distance: 0.3, limited_rot_speed: 0.45, limited_trans_speed: 0.25} + base_local_planner: base_local_planner/TrajectoryPlannerROS + TrajectoryPlannerROS: + min_in_place_vel_theta: 1.0 + escape_vel: -0.1 # -0.1 + vx_samples: 10 + meter_scoring: true + pdist_scale: 5.0 + gdist_scale: 3.2 + occdist_scale: 0.1 + dwa: true + recovery_behavior_enabled: true + recovery_behaviors: + - name: "conservative_reset" + type: "clear_costmap_recovery/ClearCostmapRecovery" + - name: "rotate_recovery" + type: "rotate_recovery/RotateRecovery" + frequency: 20.0 + sim_granularity: 0.017 + - name: "aggressive_reset" + type: "clear_costmap_recovery/ClearCostmapRecovery" + conservative_reset: + reset_distance: 1.0 # 3.0 + aggressive_reset: + reset_distance: 0.2 # 0.5 + move_slow_and_clear: + clearing_distance: 0.5 + limited_distance: 0.3 + limited_rot_speed: 0.45 + limited_trans_speed: 0.25 + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml index 2f82cba059..dbe9a8382e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml @@ -77,6 +77,16 @@ + + inflater: + inflation_radius: 1.0 # 0.7 + cost_scaling_factor: 3.0 # 25.0 default 10, increasing factor decrease the cost value + obstacles: + min_obstacle_height: 0.05 + # default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide) + update_frequency: 10.0 + footprint_padding: 0.05 + diff --git a/jsk_fetch_robot/jsk_fetch_startup/package.xml b/jsk_fetch_robot/jsk_fetch_startup/package.xml index 2c5481f28f..ee411f62e7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/package.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/package.xml @@ -28,6 +28,7 @@ amcl map_server move_base + robot_localization app_manager diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/correct_position.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/correct_position.py index 22057b7e40..43d0a01e05 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/correct_position.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/correct_position.py @@ -22,24 +22,31 @@ def __init__(self): self.dock_pose = spot.pose self.is_docking = False + self.timer = rospy.Timer(rospy.Duration(1.0), self._cb_correct_position) def subscribe(self): - self.sub_dock = rospy.Subscriber('/battery_state', - BatteryState, - self._cb_correct_position) + self.sub_dock = rospy.Subscriber( + '/battery_state', BatteryState, self._cb) def unsubscribe(self): self.sub_dock.unregister() - def _cb_correct_position(self, msg): - if msg.is_charging and (not self.is_docking): + def _cb(self, msg): + self.is_docking = msg.is_charging + + def _cb_correct_position(self, event): + if self.is_docking: self.pos = PoseWithCovarianceStamped() self.pos.header.stamp = rospy.Time.now() self.pos.header.frame_id = 'map' self.pos.pose.pose = self.dock_pose - 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] + self.pos.pose.covariance = [1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 1e-3, 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, 1e-3] self.pub.publish(self.pos) - self.is_docking = msg.is_charging if __name__ == '__main__': diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/imu_corrector.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/imu_corrector.py new file mode 100755 index 0000000000..d6b22d565f --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/imu_corrector.py @@ -0,0 +1,27 @@ +#!/usr/bin/env python + +import rospy + +from sensor_msgs.msg import Imu + + +class ImuCorrector(object): + def __init__(self): + super(ImuCorrector, self).__init__() + self.sub = rospy.Subscriber( + '~input', Imu, self._cb, queue_size=1) + self.pub = rospy.Publisher( + '~output', Imu, queue_size=1) + + def _cb(self, msg): + msg.header.frame_id = 'base_link' + msg.angular_velocity_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 4e-6] + self.pub.publish(msg) + + +if __name__ == '__main__': + rospy.init_node('imu_corrector') + app = ImuCorrector() + rospy.spin() diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/odom_corrector.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/odom_corrector.py new file mode 100755 index 0000000000..d6f37c8f38 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/odom_corrector.py @@ -0,0 +1,31 @@ +#!/usr/bin/env python + +import rospy + +from nav_msgs.msg import Odometry + + +class OdomCorrector(object): + def __init__(self): + super(OdomCorrector, self).__init__() + self.sub = rospy.Subscriber( + '~input', Odometry, self._cb, queue_size=1) + self.pub = rospy.Publisher( + '~output', Odometry, queue_size=1) + self.covariance = [1e-3, 0, 0, 0, 0, 0, + 0, 1e-3, 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, 1e-3] + + def _cb(self, msg): + msg.pose.covariance = self.covariance + msg.twist.covariance = self.covariance + self.pub.publish(msg) + + +if __name__ == '__main__': + rospy.init_node('odom_corrector') + app = OdomCorrector() + rospy.spin()