odom frame at wrong place

asked 2022-01-23 22:53:20 -0500

Fan_Yihui gravatar image

I find my odom frame in tf at wrong position.And the robot model in rviz just run in the direction to this frame when I instruct it to go forward.But in fact, it should have run in a direction which is almost vertical.This makes it impossible to create a right map in gmapping.

code to broadcast odom tf: void pubWheelOdom() { nav_msgs::Odometry odom; Motion3I::Velocity_t vel; Motion3I::Position_t get_pos;

    motion->GetVelocit(vel);
    motion->GetOdometer(get_pos);

    geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(get_pos.yaw);
    geometry_msgs::TransformStamped odom_trans;
    static tf::TransformBroadcaster odom_broadcaster;

    odom_trans.header.stamp = ros::Time::now();
    odom_trans.header.frame_id = "odom";
    odom_trans.child_frame_id = "base_link";

    odom_trans.transform.translation.x = get_pos.x;
    odom_trans.transform.translation.y = get_pos.y;
    odom_trans.transform.translation.z = 0.0;
    odom_trans.transform.rotation = odom_quat;
    odom_broadcaster.sendTransform(odom_trans);

    odom.header.frame_id   = "odom";
    odom.child_frame_id    = "base_link";
    odom.header.stamp      = ros::Time::now();

    odom.twist.twist.linear.x  = vel.x_vel;
    odom.twist.twist.linear.y  = vel.y_vel;
    odom.twist.twist.angular.z = vel.yaw_vel;
    odom.pose.pose.position.x  = get_pos.x;
    odom.pose.pose.position.y  = get_pos.y;
    odom.pose.pose.position.z  = 0.0;
    odom.pose.pose.orientation = odom_quat;
    odom.twist.covariance[0]   = 0.0025 * abs(odom.twist.twist.linear.x);
    odom.twist.covariance[7]   = 0.0025 * abs(odom.twist.twist.linear.y);
    odom.twist.covariance[35]  = 0.0025 * abs(odom.twist.twist.angular.z);
    m_pub_wheel_odom.publish(odom);
};

and the code of urdf: <robot name="mbot">

<material name="Black"> <color rgba="0 0 0 1"/> </material> <material name="White"> <color rgba="1 1 1 0.95"/> </material> <material name="Blue"> <color rgba="0 0 1 1"/> </material> <material name="Yellow"> <color rgba="1 0.4 0 1"/> </material>

<link name="base_link"> <visual> <origin xyz=" 0 0 0" rpy="0 0 0"/> <geometry> <cylinder length="0.056" radius="0.165"/> </geometry> <material name="Yellow"/> </visual> </link>

<link name="left_wheel_link">
    <visual>
        <origin xyz="0 0 0" rpy="1.5707 0 0" />
        <geometry>
            <cylinder radius="0.035" length = "0.0147"/>
        </geometry>
        <material name="White"/>
    </visual>
</link>

<joint name="left_wheel_joint" type="continuous">
    <origin xyz="0 0.125 -0.01" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="left_wheel_link"/>
    <axis xyz="0 1 0"/>
</joint>

<link name="right_wheel_link">
    <visual>
        <origin xyz="0 0 0" rpy="1.5707 0 0" />
        <geometry>
            <cylinder radius="0.035" length = "0.0147"/>
        </geometry>
        <material name="White"/>
    </visual>
</link>

<joint name="right_wheel_joint" type="continuous">
    <origin xyz="0 -0.125 -0.01" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="right_wheel_link"/>
    <axis xyz="0 1 0"/>
</joint>

<link name="horizontal_laser_link"> <visual> <origin xyz=" 0 0 0 " rpy="0 0 0"/> <geometry> <cylinder length="0.017" radius="0.025"/> </geometry> <material name="Black"/> </visual> </link>

<joint name="laser_joint" type ...
(more)
edit retag flag offensive close merge delete