From 4958e800772cdb9f790ce42feb89ea87d4b268e7 Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Fri, 14 Aug 2015 03:44:22 +0200 Subject: [PATCH 1/1] added robot_pose_ekf --- cfg/razor.yaml | 6 +++--- launch/wild_thumper.launch | 8 ++++++++ scripts/move_base.py | 18 ++++++++++++++--- urdf/wild_thumper.urdf.xacro | 38 ++++++++++++++++++++++++++++++++++-- 4 files changed, 62 insertions(+), 8 deletions(-) diff --git a/cfg/razor.yaml b/cfg/razor.yaml index 20bffbc..65d6d44 100644 --- a/cfg/razor.yaml +++ b/cfg/razor.yaml @@ -23,11 +23,11 @@ magn_z_max: 596 # extended calibration calibration_magn_use_extended: true -magn_ellipsoid_center: [-32.6801, 82.7799, 142.354] -magn_ellipsoid_transform: [[0.993252, 0.00616743, -0.00945049], [0.00616743, 0.990730, -0.000356148], [-0.00945049, -0.000356148, 0.964502]] +magn_ellipsoid_center: [164.907, 212.010, 16.4033] +magn_ellipsoid_transform: [[0.977989, 0.00268088, 0.0115993], [0.00268088, 0.974660, 0.0151645], [0.0115993, 0.0151645, 0.982901]] # AHRS to robot calibration -imu_yaw_calibration: 180.0 +imu_yaw_calibration: 0.0 ### gyroscope gyro_average_offset_x: -29.0 diff --git a/launch/wild_thumper.launch b/launch/wild_thumper.launch index 42682bf..cc2db13 100644 --- a/launch/wild_thumper.launch +++ b/launch/wild_thumper.launch @@ -13,4 +13,12 @@ + + + + + + + + diff --git a/scripts/move_base.py b/scripts/move_base.py index 0beaf26..c4da5d0 100755 --- a/scripts/move_base.py +++ b/scripts/move_base.py @@ -18,7 +18,7 @@ class MoveBase: rospy.init_node('wild_thumper_move_base') rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived) rospy.Subscriber("imu", Imu, self.imuReceived) - self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() + #self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16) self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16) self.set_speed(0, 0) @@ -119,7 +119,7 @@ class MoveBase: odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle) # first, we'll publish the transform over tf - self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_link", "odom") + #self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom") # next, we'll publish the odometry message over ROS odom = Odometry() @@ -134,12 +134,24 @@ class MoveBase: odom.pose.pose.orientation.y = odom_quat[1] odom.pose.pose.orientation.z = odom_quat[2] odom.pose.pose.orientation.w = odom_quat[3] + odom.pose.covariance[0] = 1e-3 # x + odom.pose.covariance[7] = 1e-3 # y + odom.pose.covariance[14] = 1e-3 # z + odom.pose.covariance[21] = 0.1 # rotation about X axis + odom.pose.covariance[28] = 0.1 # rotation about Y axis + odom.pose.covariance[35] = 0.1 # rotation about Z axis # set the velocity - odom.child_frame_id = "base_link" + odom.child_frame_id = "base_footprint" odom.twist.twist.linear.x = speed_trans odom.twist.twist.linear.y = 0.0 odom.twist.twist.angular.z = speed_rot + odom.twist.covariance[0] = 1e-3 # x + odom.twist.covariance[7] = 1e-3 # y + odom.twist.covariance[14] = 1e-3 # z + odom.twist.covariance[21] = 0.1 # rotation about X axis + odom.twist.covariance[28] = 0.1 # rotation about Y axis + odom.twist.covariance[35] = 0.1 # rotation about Z axis # publish the message self.pub_odom.publish(odom) diff --git a/urdf/wild_thumper.urdf.xacro b/urdf/wild_thumper.urdf.xacro index ceb3df3..c783cff 100644 --- a/urdf/wild_thumper.urdf.xacro +++ b/urdf/wild_thumper.urdf.xacro @@ -5,14 +5,48 @@ - + + + + + + + + + + + + + + + + + + + + + + + - + + + + + + + + + + + + + -- 2.39.2