Skip to content
Snippets Groups Projects
Commit 3670e453 authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Merge branch 'kinetic_migration' into 'master'

Kinetic migration

See merge request seat_adc/seat_car_simulator!1
parents 3443d821 4cf26a4b
No related branches found
No related tags found
1 merge request!1Kinetic migration
Showing
with 116 additions and 60 deletions
......@@ -11,39 +11,38 @@ http://www.autonomousdrivingchallenge.com
## Installing
Install modelcar basic packages, because we need its odometry package
1. Clone AutoModelCar version-3 repo, because we need its odometry package
```
mkdir -p ~/seat
cd ~/seat
git clone -b version-3 https://github.com/AutoModelCar/model_car.git model_car_3
#git clone -b version-3-kinetic https://github.com/AutoModelCar/model_car.git model_car_3
source /opt/ros/indigo/setup.bash
#source /opt/ros/kinetic/setup.bash
cd ~/seat/model_car_3/catkin_ws
rm -rf build devel
# We actually only need the odometry package
catkin_make --only-pkg-with-deps odometry
wget http://ftp.imp.fu-berlin.de/pub/autonomos/data/modelcar/software-packages/v3/kinetic/amd64/modelcar-basic-packages.deb
sudo dpkg -i modelcar-basic-packages.deb
source /opt/ros/modelcar/catkin_ws/install/setup.bash
# You can add this last line to you ~/.bashrc
```
2. Create our catkin_ws workspace, overlaying model_car_3/catkin_ws
Create our catkin_ws workspace, overlaying /opt/ros/modelcar/install/catkin_ws
```
source ~/seat/model_car_3/catkin_ws/devel/setup.bash
mkdir -p ~/seat/catkin_ws/src
cd ~/seat/catkin_ws
source /opt/ros/modelcar/catkin_ws/install/setup.bash
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin_make
source ~/seat/catkin_ws/devel/setup.bash
# You can/should add this last line to you ~/.bashrc
source ~/catkin_ws/devel/setup.bash
# You can add this last line to you ~/.bashrc
```
3. Clone simulator in catkin_ws
Clone simulator in catkin_ws
```
roscd; cd ../src
git clone https://gitlab.iri.upc.edu/seat_adc/seat_car_simulator.git
rosdep install -i --from-paths seat_car_simulator
roscd; cd ..
catkin_make --only-pkg-with-deps seat_car_simulator
catkin_make
```
## Running
......
......@@ -10,7 +10,7 @@
<arg name="height" default="0.25"/>
<arg name="model" default="$(find road_description)/urdf/box/box.xacro"/>
<param name="$(arg name)_description" command="$(find xacro)/xacro '$(arg model)' name:=$(arg name) length:=$(arg length) width:=$(arg width) height:=$(arg height)" />
<param name="$(arg name)_description" command="$(find xacro)/xacro --inorder '$(arg model)' name:=$(arg name) length:=$(arg length) width:=$(arg width) height:=$(arg height)" />
<node name="$(arg name)_state_publisher"
pkg ="robot_state_publisher"
......
......@@ -11,7 +11,7 @@
<arg name="parent" default="$(arg name)_base_link"/>
<param name="$(arg name)_description"
command="$(find xacro)/xacro '$(arg model_path)'
command="$(find xacro)/xacro --inorder '$(arg model_path)'
name:=$(arg name)
parent:=$(arg parent)
height:=2.0"
......
......@@ -9,7 +9,7 @@
<arg name="height" default="0.25"/>
<arg name="model" default="$(find road_description)/urdf/cylinder/cylinder.xacro"/>
<param name="$(arg name)_description" command="$(find xacro)/xacro '$(arg model)' name:=$(arg name) radius:=$(arg radius) height:=$(arg height)" />
<param name="$(arg name)_description" command="$(find xacro)/xacro --inorder '$(arg model)' name:=$(arg name) radius:=$(arg radius) height:=$(arg height)" />
<node name="$(arg name)_state_publisher"
pkg ="robot_state_publisher"
......
......@@ -10,7 +10,7 @@
<arg name="parent" default="$(arg name)_base_link"/>
<param name="$(arg name)_description"
command="$(find xacro)/xacro.py '$(arg model_path)'
command="$(find xacro)/xacro --inorder '$(arg model_path)'
name:=$(arg name)
parent:=$(arg parent)">
</param>
......
......@@ -10,7 +10,7 @@
<arg name="parent" default="$(arg name)_base_link"/>
<param name="$(arg name)_description"
command="$(find xacro)/xacro '$(arg model_path)'
command="$(find xacro)/xacro --inorder '$(arg model_path)'
name:=$(arg name)
parent:=$(arg parent)"
/>
......
......@@ -4,7 +4,9 @@
<xacro:include filename="$(find road_description)/urdf/roads/road_piece.xacro" />
<xacro:include filename="$(find road_description)/urdf/roads/road_ground.xacro" />
<link name="$(arg parent)">
<link name="$(arg parent)"/>
<link name="$(arg parent)_body">
<inertial>
<mass value="100"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
......@@ -18,6 +20,12 @@
<material name="red"/>
</collision>
</link>
<joint name="joint_$(arg parent)_to_$(arg parent)_body" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="$(arg parent)"/>
<child link="$(arg parent)_body" />
</joint>
<xacro:road name="$(arg name)0" parent="$(arg parent)" dae="full" size="12">
<origin xyz="0.0 -5.07 0" rpy="0 0 0"/>
......
......@@ -4,7 +4,9 @@
<xacro:include filename="$(find road_description)/urdf/roads/road_piece.xacro" />
<xacro:include filename="$(find road_description)/urdf/roads/road_ground.xacro" />
<link name="$(arg parent)">
<link name="$(arg parent)"/>
<link name="$(arg parent)_body">
<inertial>
<mass value="100"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
......@@ -18,6 +20,12 @@
<material name="red"/>
</collision>
</link>
<joint name="joint_$(arg parent)_to_$(arg parent)_body" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="$(arg parent)"/>
<child link="$(arg parent)_body" />
</joint>
<xacro:road name="$(arg name)0" parent="$(arg parent)" dae="test" size="12">
<origin xyz="0 -4.5 0" rpy="0 0 0"/>
......
......@@ -12,7 +12,7 @@
respawn="false"
output="screen"
ns="seat_car"
args="joint_state_controller car_cont --shutdown-timeout 1"/>
args="joint_state_controller car_cont"/>
</launch>
......@@ -5,11 +5,11 @@
<arg name="model" default="car"/>
<param name="robot_description"
command="$(find xacro)/xacro '$(find seat_car_description)/urdf/$(arg model).xacro'" />
command="$(find xacro)/xacro --inorder '$(find seat_car_description)/urdf/$(arg model).xacro'" />
<node pkg="robot_state_publisher" type="state_publisher" name="tf_broadcaster_$(arg name)">
<node pkg="robot_state_publisher" type="robot_state_publisher" name="tf_broadcaster_$(arg name)">
<param name="publish_frequency" type="double" value="50.0"/>
<remap from="/joint_states" to="/$(arg name)/joint_states" />
</node>
</launch>
\ No newline at end of file
</launch>
......@@ -7,6 +7,9 @@
<xacro:property name="wheel_width" value="0.001" />
<link name="base_link">
</link>
<link name="body">
<inertial>
<mass value="6" />
<origin xyz="0.15971917 0.00000000 0.00197764" />
......@@ -28,6 +31,12 @@
</geometry>
</collision>
</link>
<joint name="base_link_to_body" type="fixed">
<origin xyz="0.0 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="body" />
</joint>
<joint name="base_link_rear_left_wheel_joint" type="revolute">
<origin xyz="0.0 -0.0825 0" rpy="${PI/2.0} 0 0" />
......@@ -41,10 +50,10 @@
<transmission name="tran_rear_left">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_link_rear_left_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rear_left_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
......@@ -84,10 +93,10 @@
<transmission name="tran_rear_right">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_link_rear_right_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rear_right_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
......@@ -128,10 +137,10 @@
<transmission name="tran_front_left_axel">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_link_front_left_axel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_left_axel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
......@@ -158,10 +167,10 @@
<transmission name="tran_front_left_wheel">
<type>transmission_interface/SimpleTransmission</type>
<joint name="front_left_axel_front_left_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_left_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
......@@ -202,10 +211,10 @@
<transmission name="tran_front_right_axel">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_link_front_right_axel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_right_axel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
......@@ -232,10 +241,10 @@
<transmission name="tran_front_right_wheel">
<type>transmission_interface/SimpleTransmission</type>
<joint name="front_right_axel_front_right_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="front_right_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
......@@ -263,4 +272,4 @@
</collision>
</link>
</robot>
\ No newline at end of file
</robot>
......@@ -32,11 +32,6 @@
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<frameName>${front_camera_name}_rgb_optical_frame</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
......
......@@ -30,6 +30,13 @@
<near>0.2</near>
<far>15.0</far>
</clip>
<distortion>
<k1>-0.25</k1>
<k2>0.12</k2>
<k3>0.0</k3>
<p1>-0.00028</p1>
<p2>-0.00005</p2>
</distortion>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
......@@ -48,11 +55,6 @@
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudCutoff>0.4</pointCloudCutoff>
<hackBaseline>0.007</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
<CxPrime>0.0</CxPrime>
<Cx>0.0</Cx>
<Cy>0.0</Cy>
......
......@@ -13,6 +13,7 @@
</gazebo>
<gazebo reference="${top_camera_name}">
<!-- -->
<sensor type="camera" name="${top_camera_name}">
<update_rate>${rate}</update_rate>
<camera name="${top_camera_name}">
......@@ -26,6 +27,13 @@
<near>0.02</near>
<far>300</far>
</clip>
<distortion>
<k1>-0.25</k1>
<k2>0.12</k2>
<k3>0.0</k3>
<p1>-0.00028</p1>
<p2>-0.00005</p2>
</distortion>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
......@@ -40,15 +48,42 @@
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${top_camera_name}_optical</frameName>
<hackBaseline>0.07</hackBaseline>
<!-- Distortion not supported on Gazebo 2.2
<distortionK1>-0.252292</distortionK1>
<distortionK2>0.035156</distortionK2>
<distortionK3>0.00057</distortionK3>
<distortionT1>-0.002072</distortionT1>
<distortionT2>0.0</distortionT2>
-->
</plugin>
</sensor>
-->
<!-- wideanglecamera: does not work? black screen -->
<!--
<sensor name="${top_camera_name}" type="wideanglecamera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<lens>
<type>gnomonical</type>
<scale_to_hfov>true</scale_to_hfov>
<cutoff_angle>1.5707</cutoff_angle>
<env_texture_size>512</env_texture_size>
</lens>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<plugin name="${top_camera_name}_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>${rate}</updateRate>
<cameraName>usb_cam</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${top_camera_name}_optical</frameName>
</plugin>
</sensor>
-->
</gazebo>
</robot>
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment