Robot pose is improper in Gazebo & Rviz
I have launched the navigation stack in gazebo and Rviz, when i gave the initial 2D pose in rviz the robot appears in side ways. The left side of the robot is considered as front portion in Rviz and gazebo.
I have exported the model from Solidworks where my X-axis was aligned in side ways of the robot. Is that the problem here? Then my localization is poor, does this pose error has anything to do with localization. How to fix this, is there any possibility to edit the URDF to change the pose?
URDF
<?xml version="1.0"?>
<robot
name="jmbot1.2">
<link
name="base_link">
<inertial>
<origin
xyz="4.37890354126393E-17 0.00236901195255572 6.55292757021008E-18"
rpy="0 0 0" />
<mass
value="0.553388494231952" />
<inertia
ixx="0.0061380231979678"
ixy="-7.4245754982948E-20"
ixz="3.98664982078876E-19"
iyy="0.0102825937754972"
iyz="-3.90792618692798E-19"
izz="0.00414996053647982" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot2_description/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.749019607843137 0.749019607843137 0.749019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot2_description/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="Wheel_L">
<inertial>
<origin
xyz="-0.0394771489417549 -8.67361737988404E-19 5.20417042793042E-18"
rpy="0 0 0" />
<mass
value="0.450643534719172" />
<inertia
ixx="0.000916081598048294"
ixy="6.78545238432742E-22"
ixz="5.25584106042723E-20"
iyy="0.000533948766711723"
iyz="-5.42101086242752E-20"
izz="0.000533948766711723" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot2_description/meshes/Wheel_L.STL" />
</geometry>
<material
name="">
<color
rgba="0.749019607843137 0.749019607843137 0.749019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot2_description/meshes/Wheel_L.STL" />
</geometry>
</collision>
</link>
<joint
name="Wheel_L"
type="continuous">
<origin
xyz="0.135 0 -0.0150000000000001"
rpy="-2.71270653405672 1.43472398876874E-16 -3.14159265358979" />
<parent
link="base_link" />
<child
link="Wheel_L" />
<axis
xyz="1 0 0" />
</joint>
<link
name="Wheel_R">
<inertial>
<origin
xyz="-0.0394771489417549 8.67361737988404E-17 6.59194920871187E-17"
rpy="0 0 0" />
<mass
value="0.450643534719172" />
<inertia
ixx="0.000916081598048294"
ixy="2.5544898321056E-20"
ixz="-2.19457985353437E-21"
iyy="0.000533948766711724"
iyz="-8.13151629364128E-20"
izz="0.000533948766711723" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot2_description/meshes/Wheel_R.STL" />
</geometry>
<material
name="">
<color
rgba="0.749019607843137 0.749019607843137 0.749019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot2_description/meshes/Wheel_R.STL" />
</geometry>
</collision>
</link>
<joint
name="Wheel_R"
type="continuous">
<origin
xyz="-0.135 0 -0.015"
rpy="2.51202191489506 0 0" />
<parent
link="base_link" />
<child
link="Wheel_R" />
<axis
xyz="-1 0 0" />
</joint>
<link
name="Castor_F">
<inertial>
<origin
xyz="-5.55111512312578E-17 1.45716771982052E-16 0.0311642520583202"
rpy="0 0 0" />
<mass
value="0.0565552012132997" />
<inertia
ixx="2.44755054701354E-05"
ixy="0"
ixz="-5.19674657761973E-21"
iyy="2.44755054701354E-05"
iyz="-1.16131199025338E-20"
izz="7.43413937311511E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot2_description/meshes/Castor_F.STL" />
</geometry ...