Skip to content

Commit

Permalink
merge
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Jun 21, 2017
2 parents 636499a + 2d9173e commit 77e6c79
Show file tree
Hide file tree
Showing 3 changed files with 98 additions and 96 deletions.
187 changes: 96 additions & 91 deletions prius_description/urdf/prius.urdf
Original file line number Diff line number Diff line change
@@ -1,30 +1,30 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="prius">

<gazebo reference="front_left_wheel">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<minDepth>0.005</minDepth>
<kp>1e8</kp>
</gazebo>
<gazebo reference="front_right_wheel">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<minDepth>0.005</minDepth>
<kp>1e8</kp>
</gazebo>
<gazebo reference="rear_left_wheel">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<minDepth>0.005</minDepth>
<kp>1e8</kp>
</gazebo>
<gazebo reference="rear_right_wheel">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<minDepth>0.005</minDepth>
<kp>1e8</kp>
</gazebo>
<gazebo reference="front_left_wheel">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<minDepth>0.005</minDepth>
<kp>1e8</kp>
</gazebo>
<gazebo reference="front_right_wheel">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<minDepth>0.005</minDepth>
<kp>1e8</kp>
</gazebo>
<gazebo reference="rear_left_wheel">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<minDepth>0.005</minDepth>
<kp>1e8</kp>
</gazebo>
<gazebo reference="rear_right_wheel">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<minDepth>0.005</minDepth>
<kp>1e8</kp>
</gazebo>

<link name="chassis">
<visual>
Expand Down Expand Up @@ -183,75 +183,80 @@
<parent link="chassis"/>
<child link="steering_wheel"/>
<axis xyz="0 1 0.84365"/>
</joint>
</joint>

<joint name="fl_steer_joint" type="continuous">
<parent link="chassis"/>
<child link="fl_axle"/>
<origin xyz="0.767 -1.41 0.3" rpy="-0.089 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="fr_steer_joint" type="continuous">
<parent link="chassis"/>
<child link="fr_axle"/>
<origin xyz="-0.767 -1.41 0.3" rpy="-0.089 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="front_left_wheel_joint" type="continuous">
<parent link="fl_axle"/>
<child link="front_left_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="front_right_wheel_joint" type="continuous">
<parent link="fr_axle"/>
<child link="front_right_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_left_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_left_wheel"/>
<origin xyz="0.793 1.45 0.3" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_right_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_right_wheel"/>
<origin xyz="-0.793 1.45 0.3" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="fl_steer_joint" type="continuous">
<parent link="chassis"/>
<child link="fl_axle"/>
<origin xyz="0.767 -1.41 0.3" rpy="-0.089 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="fr_steer_joint" type="continuous">
<parent link="chassis"/>
<child link="fr_axle"/>
<origin xyz="-0.767 -1.41 0.3" rpy="-0.089 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="front_left_wheel_joint" type="continuous">
<parent link="fl_axle"/>
<child link="front_left_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="front_right_wheel_joint" type="continuous">
<parent link="fr_axle"/>
<child link="front_right_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_left_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_left_wheel"/>
<origin xyz="0.793 1.45 0.3" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_right_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_right_wheel"/>
<origin xyz="-0.793 1.45 0.3" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>

<gazebo>
<plugin name="pruis_hybrid_drive" filename="libPriusHybridPlugin.so">
<!-- ... plugin parameters ... -->
</plugin>
</gazebo>

<gazebo reference="chassis">
<sensor name='laser' type='ray'>
<pose frame=''>0 -2.4 0.5 0 0.05 -1.5707</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.26889</min_angle>
<max_angle>2.2689</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.2</min>
<max>30</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name='laser' filename='libRayPlugin.so'/>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>1</visualize>
</sensor>
</gazebo>
<gazebo reference="chassis">
<sensor name='laser' type='ray'>
<pose frame=''>0 -2.4 0.5 0 0.05 -1.5707</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.26889</min_angle>
<max_angle>2.2689</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.2</min>
<max>30</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name='laser' filename='libRayPlugin.so'/>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>1</visualize>
</sensor>
</gazebo>


</robot>
</robot>
6 changes: 1 addition & 5 deletions prius_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,4 @@ install(TARGETS PriusHybridPlugin
)

install(DIRECTORY models DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})



# TODO(tfoote) replace installers add_subdirectory(models)
# TODO(tfoote) replace installers add_subdirectory(worlds)
install(DIRECTORY worlds DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
1 change: 1 addition & 0 deletions prius_plugin/plugins/PriusHybridPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -249,6 +249,7 @@ PriusHybridPlugin::~PriusHybridPlugin()
/////////////////////////////////////////////////
void PriusHybridPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
{
gzinfo << "PriusHybridPlugin Loading Parameters" << std::endl;
this->dataPtr->model = _model;
this->dataPtr->world = this->dataPtr->model->GetWorld();
auto physicsEngine = this->dataPtr->world->Physics();
Expand Down

0 comments on commit 77e6c79

Please sign in to comment.