Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update Gazebo with new masses and sensor suite #193

Merged
merged 45 commits into from
Jun 17, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
45 commits
Select commit Hold shift + click to select a range
67b4925
added all the gps stuffs
chsahit Mar 1, 2017
1d0fe77
it renders!
chsahit Mar 8, 2017
26f99b3
included imu in navsatfix
chsahit Mar 12, 2017
9f53c67
the car urdf now has both an imu and a urdf
chsahit Mar 12, 2017
ba410f1
Revert "joint states is being subscribed to by sim_car_interface and …
chsahit Mar 14, 2017
07b554a
Merge branch 'buzzmobile_modeling' of https://github.com/gtagency/buz…
chsahit Mar 14, 2017
ab79aab
many changes, makes car move, albeit slowly
irapha Mar 15, 2017
92242b0
Merge branch 'buzzmobile_modeling' of https://github.com/gtagency/buz…
chsahit Apr 4, 2017
29d080b
Merge branch 'master' of https://github.com/gtagency/buzzmobile into …
chsahit Apr 5, 2017
9de7079
Merge branch 'master' of https://github.com/gtagency/buzzmobile into …
chsahit Apr 5, 2017
47c7ae6
updated masses and inertials
chsahit Apr 19, 2017
d31f5d2
IT WORKS
chsahit Apr 19, 2017
e018005
fixed most mistakes requested on the PR
chsahit May 11, 2017
8f0486f
Merge branch 'master' of https://github.com/gtagency/buzzmobile into …
chsahit May 11, 2017
3f9501f
more precise URDF and specified in constants.yaml problem with rospar…
chsahit May 13, 2017
f1d5822
added better docs in constants.yaml/steering.py and fixed sim.launch
chsahit May 14, 2017
6b68a8a
turns out we don't have to update max_speed in multiple places
chsahit May 14, 2017
06989cb
Add pyrostest dependency.
joshuamorton May 29, 2017
bd05a75
Delete old builting 'pyrostest'.
joshuamorton May 29, 2017
35cdec3
Changed version to reflect reality.
joshuamorton May 29, 2017
5157f90
Convert tests to use pyrostest instead of builtin.
joshuamorton May 29, 2017
3d00610
No longer box tests.
joshuamorton May 29, 2017
62a44cc
Merge pull request #206 from gtagency/convert-to-pyros
joshuamorton Jun 1, 2017
a90bccc
Hopefully fix build.
joshuamorton Jun 3, 2017
65f92d6
Try a different way.
joshuamorton Jun 3, 2017
a0a1105
Revert "Try a different way."
joshuamorton Jun 3, 2017
fc814dc
Add system deps.
joshuamorton Jun 3, 2017
1ed6df1
Merge pull request #207 from gtagency/fix-build
joshuamorton Jun 8, 2017
f69d6bc
added all the gps stuffs
chsahit Mar 1, 2017
a641b75
it renders!
chsahit Mar 8, 2017
797e0cd
included imu in navsatfix
chsahit Mar 12, 2017
e3dbaad
the car urdf now has both an imu and a urdf
chsahit Mar 12, 2017
b78abc6
Revert "joint states is being subscribed to by sim_car_interface and …
chsahit Mar 14, 2017
63542c8
many changes, makes car move, albeit slowly
irapha Mar 15, 2017
c01014e
updated masses and inertials
chsahit Apr 19, 2017
2d444eb
IT WORKS
chsahit Apr 19, 2017
1f2526a
fixed most mistakes requested on the PR
chsahit May 11, 2017
7dfa79e
more precise URDF and specified in constants.yaml problem with rospar…
chsahit May 13, 2017
02fe2fc
added better docs in constants.yaml/steering.py and fixed sim.launch
chsahit May 14, 2017
14a9ab9
turns out we don't have to update max_speed in multiple places
chsahit May 14, 2017
3f2d0aa
it works now??
chsahit Jun 11, 2017
424d0df
Merge branch 'navsatfix' of https://github.com/gtagency/buzzmobile in…
chsahit Jun 11, 2017
9bf0b1f
bzm now compiles
chsahit Jun 11, 2017
7c0eba0
shrunk the clock down a lot
chsahit Jun 11, 2017
305e67c
added a longer timeout
chsahit Jun 11, 2017
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion buzzmobile/constants.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ wheel_separation: 1.3716 # distance between left and right wheels in meters
max_steering_angle: 0.262 # radians (=15 degrees)

# Max speed of buzzmobile in m/s
max_speed: 0.2
max_speed: 0.2 #TODO: measure the max speed.

# Resolution of potential paths, that is to say, the higher this number, the
# more tentacles/linear paths will be judged
Expand Down
2 changes: 1 addition & 1 deletion buzzmobile/launch/includes/gps.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<launch>
<node pkg="buzzmobile" name="bearing" type="bearing.py"/>
<node pkg="buzzmobile" name="gps_mapper" type="gps_mapper.py"/>
<node pkg="buzzmobile" name="gps_mapper" type="gps_mapper.py" output="screen"/>
</launch>
5 changes: 2 additions & 3 deletions buzzmobile/launch/includes/sim_spawn_car.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,13 @@
<node pkg="controller_manager" name="spawner" type="spawner"
args="left_wheel_effort_controller right_wheel_effort_controller
left_steer_position_controller right_steer_position_controller
joint_state_controller"/>

joint_state_controller --timeout=30000"/>

<!-- Spawn Car -->
<param name="robot_description" command="cat $(find buzzmobile)/simulation/models/car/car_joints.urdf"/>
<node pkg="gazebo_ros" name="spawn_model" type="spawn_model" output="screen"
args="-file $(find buzzmobile)/simulation/models/car/car_joints.urdf
-urdf -model buzzmobile
-x 0 -y 0 -z 0
-x 0 -y 0 -z 0.1
-R 0 -P 0 -Y 0"/>
</launch>
2 changes: 1 addition & 1 deletion buzzmobile/launch/simulation.launch
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<node pkg="gazebo_ros" name="gazebo_gui" type="gzclient"/>
</group>

<!-- Spawn car -->
<!-- Spawn Car -->
<!-- node pkg="buzzmobile" name="sim_spawn_car" type="sim_spawn_car.sh"/ -->
<include file="$(find buzzmobile)/launch/includes/sim_spawn_car.launch"/>
</launch>
2 changes: 2 additions & 0 deletions buzzmobile/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
<build_depend>hector_gazebo</build_depend>
<build_depend>gazebo_ros_control</build_depend>
<build_depend>joint_state_controller</build_depend>
<build_depend>effort_controllers</build_depend>

<run_depend>usb_cam</run_depend>
<run_depend>nmea_navsat_driver</run_depend>
Expand All @@ -49,6 +50,7 @@
<run_depend>hector_gazebo</run_depend>
<run_depend>gazebo_ros_control</run_depend>
<run_depend>joint_state_controller</run_depend>
<run_depend>effort_controllers</run_depend>

<export>
<gazebo_ros gazebo_model_path="${prefix}/simulation/models/world/materials"/>
Expand Down
4 changes: 2 additions & 2 deletions buzzmobile/plan/steering/steering.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,15 +33,15 @@
PIXELS_PER_M = rospy.get_param('pixels_per_m')
HEIGHT = rospy.get_param('image_height')
WIDTH = rospy.get_param('image_width')
MAX_ANGLE = rospy.get_param('max_steering_angle')
MAX_ANGLE = rospy.get_param('max_steering_angle', 1.0)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i dont think this , 1.0 is needed (see prev discussions)

TRAVEL_DISTANCE = rospy.get_param('travel_distance')
NUM_POINTS = rospy.get_param('num_points_in_tentacle')
WHEEL_BASE = rospy.get_param('wheel_base')
ANGLE_MULTIPLIER = rospy.get_param('angle_multiplier')
BRAKING_DISTANCE = rospy.get_param('braking_distance')
THRESHHOLD = rospy.get_param('braking_score_threshhold')
BUZZMOBILE_WIDTH = rospy.get_param('buzzmobile_width')
MAX_SPEED = rospy.get_param('max_speed', 1.0)
MAX_SPEED = rospy.get_param('max_speed')

IMMEDIATE_FUTURE_MASK = np.zeros((HEIGHT, WIDTH), np.uint8)
cv2.circle(IMMEDIATE_FUTURE_MASK, (WIDTH//2, HEIGHT),
Expand Down
3 changes: 1 addition & 2 deletions buzzmobile/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,11 @@
'polyline==1.3.1',
'pylint',
'pytest==3.0.3',
'pytest-xdist==1.15.0',
'pyyaml==3.12',
'rospkg==1.0.41',
'ds4drv', # requires apt-get install python-dev
'empy==3.3.2', # required to make catkin_make work
'netifaces==0.10.5', # required for testing
'psutil==5.1.3',
'pyrostest>=0.1.2', # required for testing
],
)
74 changes: 47 additions & 27 deletions buzzmobile/simulation/models/car/car_joints.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@
<link name="chassis">
<inertial>
<origin xyz="0 0 0"/>
<mass value="5.0"/>
<inertia ixx="0.10595165" ixy="-0.002487144" ixz="0.011981253" iyy="0.126271962" iyz="0.011832006" izz="0.033185337"/>
<mass value="136.0"/>
<inertia ixx="39179.495" ixy="-257.203201" ixz="3771.586" iyy="95397.6332" iyz="-20.60398" izz="94045.9387"/>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

YAY CORRECT INERTIALS?

Copy link
Member Author

@chsahit chsahit May 9, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yup! thanks to Matt and Wolfram mathworld!

</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
Expand All @@ -24,19 +24,18 @@
<material>Gazebo/Grey</material>
</gazebo>


<link name="back_axle">
<inertial> <!--Null inertia-->
<mass value="0.001"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
<mass value="3.311"/>
<inertia ixx="0.225889" ixy="0" ixz="0" iyy="1041.8041" iyz="0" izz="1041.8041"/>
</inertial>
</link>

<link name="wheel_back_left">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0" />
<mass value="0.1" />
<inertia ixx="0.000405599" ixy="0.0" ixz="0.0" iyy="0.000405599" iyz="0.0" izz="0.000518265" />
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.132" ixy="0.0" ixz="0.0" iyy="0.132" iyz="0.0" izz="0.263"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
Expand All @@ -59,12 +58,12 @@

<link name="wheel_back_right">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0" />
<mass value="0.1" />
<inertia ixx="0.000405599" ixy="0.0" ixz="0.0" iyy="0.000405599" iyz="0.0" izz="0.000518265" />
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.132" ixy="0.0" ixz="0.0" iyy="0.132" iyz="0.0" izz="0.263"/>
</inertial>
<visual>
<origin rpy="0 0 3.14" xyz="0 0 0"/>
<origin rpy="0 0 3.14" xyz="0 -0.645 0"/>
<geometry>
<mesh filename="package://buzzmobile/simulation/models/car/wheel_mesh.dae"/>
</geometry>
Expand All @@ -84,16 +83,16 @@

<link name="steering_front_left">
<inertial> <!--Null inertia-->
<mass value="0.001"/>
<mass value="0.1"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
</link>

<link name="wheel_front_left">
<inertial>
<origin xyz="0 0 0" />
<mass value="0.1" />
<inertia ixx="0.000405599" ixy="0.0" ixz="0.0" iyy="0.000405599" iyz="0.0" izz="0.000518265" />
<origin xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.132" ixy="0.0" ixz="0.0" iyy="0.132" iyz="0.0" izz="0.263"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
Expand All @@ -115,16 +114,16 @@

<link name="steering_front_right">
<inertial> <!--Null inertia-->
<mass value="0.001"/>
<mass value="0.1"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
</link>

<link name="wheel_front_right">
<inertial>
<origin xyz="0 0 0" />
<mass value="0.1" />
<inertia ixx="0.000405599" ixy="0.0" ixz="0.0" iyy="0.000405599" iyz="0.0" izz="0.000518265" />
<origin xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.132" ixy="0.0" ixz="0.0" iyy="0.132" iyz="0.0" izz="0.263"/>
</inertial>
<visual>
<origin rpy="0 0 3.14" xyz="0 0 0"/>
Expand Down Expand Up @@ -176,6 +175,21 @@
</gazebo>


<link name="gps"/>
<gazebo>
<plugin name="gazebo_sensor" filename="libhector_gazebo_ros_gps.so">
<alwaysOn>1</alwaysOn>
<updateRate>10.0</updateRate>
<bodyName>base_footprint</bodyName>
<topicName>fix</topicName>
<velocityTopicName>fix_velocity</velocityTopicName>
<drift>0.0 0.0 0.0</drift>
<gaussianNoise>0.0 0.0 0.0</gaussianNoise>
<velocityDrift>0 0 0</velocityDrift>
<velocityGaussianNoise>0.0 0.0 0.0</velocityGaussianNoise>
</plugin>
</gazebo>

<link name="imu"/>
<gazebo>
<plugin filename="libhector_gazebo_ros_imu.so" name="imu_sensor">
Expand Down Expand Up @@ -267,7 +281,7 @@
<joint name="base_footprint_to_chassis" type="fixed">
<parent link="base_footprint"/>
<child link="chassis"/>
<origin xyz="0 0 0.036" rpy="0 0 0"/>
<origin xyz="0 0 0.3302" rpy="0 0 0"/>
</joint>

<joint name="chassis_to_back_axle" type="fixed">
Expand All @@ -279,20 +293,20 @@
<joint name="axle_to_left_wheel" type="continuous">
<parent link="back_axle"/>
<child link="wheel_back_left"/>
<origin xyz="0 0.14439 0" rpy="0 0 0"/>
<origin xyz="0 0.645 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="axle_to_right_wheel" type="continuous">
<parent link="back_axle"/>
<child link="wheel_back_right"/>
<origin xyz="0 -0.14439 0" rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>

<joint name="chassis_to_left_steering" type="revolute">
<parent link="chassis"/>
<child link="steering_front_left"/>
<origin xyz="0.33246 0.14366 0" rpy="0 0 0"/>
<origin xyz="2.032 0.645 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-0.366519" upper="0.366519" effort="100000.0" velocity="1000000.0"/>
</joint>
Expand All @@ -306,7 +320,7 @@
<joint name="chassis_to_right_steering" type="revolute">
<parent link="chassis"/>
<child link="steering_front_right"/>
<origin xyz="0.33246 -0.14366 0" rpy="0 0 0"/>
<origin xyz="2.032 -0.645 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-0.366519" upper="0.366519" effort="1000.0" velocity="1000.0"/>
</joint>
Expand Down Expand Up @@ -342,15 +356,21 @@
<joint name="lidar_joint" type="fixed">
<parent link="chassis"/>
<child link="laser"/>
<origin xyz="0.255 0 0.110" rpy="0 0 0"/>
<origin xyz="2.182 0 0" rpy="0 0 0"/>
</joint>

<joint name="gps" type="fixed">
<parent link="chassis"/>
<child link="gps"/>
<origin xyz="0 0 0.1778" rpy="0 0 0"/>
</joint>
<joint name="imu" type="fixed">
<parent link="chassis"/>
<child link="imu"/>
<origin xyz="0 0 0.1778" rpy="0 0 0"/>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
</joint>


<!--Actuators-->

<gazebo>
Expand Down
Loading