# 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
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)
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()
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)
<link name="base_link">
<visual>
- <origin xyz="0.02 0.165 0.2" rpy="${PI} 0 ${-PI/2}"/>
+ <origin xyz="0.09 -0.02 0.07" rpy="${PI} 0 ${-PI/2}"/>
<geometry>
<mesh filename="package://wild_thumper/meshes/wild_thumper_assembly_corrected.stl" scale="0.001 0.001 0.001" />
</geometry>
</visual>
</link>
+ <link name="base_footprint">
+ <visual>
+ <geometry>
+ <box size="0.28 0.31 0.0"/>
+ </geometry>
+ <material name="grey">
+ <color rgba="0.5 0.5 0.5 0.5"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="base_imu_link">
+ <visual>
+ <geometry>
+ <box size="0.041 0.028 0.002"/>
+ </geometry>
+ <material name="red">
+ <color rgba="1 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
<xacro:asus_camera name="camera" parent="base_link">
- <origin xyz="0 0.19 0.15" rpy="0 0 0"/>
+ <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
</xacro:asus_camera>
+
+ <joint name="imu_joint" type="fixed">
+ <parent link="base_link"/>
+ <child link="base_imu_link"/>
+ <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
+ </joint>
+
+ <joint name="base_link_joint" type="fixed">
+ <parent link="base_footprint"/>
+ <child link="base_link"/>
+ <origin xyz="0.0 0.0 0.13" rpy="0 0 0"/>
+ </joint>
</robot>