-
Notifications
You must be signed in to change notification settings - Fork 3
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
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 1d0fe77
it renders!
chsahit 26f99b3
included imu in navsatfix
chsahit 9f53c67
the car urdf now has both an imu and a urdf
chsahit ba410f1
Revert "joint states is being subscribed to by sim_car_interface and …
chsahit 07b554a
Merge branch 'buzzmobile_modeling' of https://github.com/gtagency/buz…
chsahit ab79aab
many changes, makes car move, albeit slowly
irapha 92242b0
Merge branch 'buzzmobile_modeling' of https://github.com/gtagency/buz…
chsahit 29d080b
Merge branch 'master' of https://github.com/gtagency/buzzmobile into …
chsahit 9de7079
Merge branch 'master' of https://github.com/gtagency/buzzmobile into …
chsahit 47c7ae6
updated masses and inertials
chsahit d31f5d2
IT WORKS
chsahit e018005
fixed most mistakes requested on the PR
chsahit 8f0486f
Merge branch 'master' of https://github.com/gtagency/buzzmobile into …
chsahit 3f9501f
more precise URDF and specified in constants.yaml problem with rospar…
chsahit f1d5822
added better docs in constants.yaml/steering.py and fixed sim.launch
chsahit 6b68a8a
turns out we don't have to update max_speed in multiple places
chsahit 06989cb
Add pyrostest dependency.
joshuamorton bd05a75
Delete old builting 'pyrostest'.
joshuamorton 35cdec3
Changed version to reflect reality.
joshuamorton 5157f90
Convert tests to use pyrostest instead of builtin.
joshuamorton 3d00610
No longer box tests.
joshuamorton 62a44cc
Merge pull request #206 from gtagency/convert-to-pyros
joshuamorton a90bccc
Hopefully fix build.
joshuamorton 65f92d6
Try a different way.
joshuamorton a0a1105
Revert "Try a different way."
joshuamorton fc814dc
Add system deps.
joshuamorton 1ed6df1
Merge pull request #207 from gtagency/fix-build
joshuamorton f69d6bc
added all the gps stuffs
chsahit a641b75
it renders!
chsahit 797e0cd
included imu in navsatfix
chsahit e3dbaad
the car urdf now has both an imu and a urdf
chsahit b78abc6
Revert "joint states is being subscribed to by sim_car_interface and …
chsahit 63542c8
many changes, makes car move, albeit slowly
irapha c01014e
updated masses and inertials
chsahit 2d444eb
IT WORKS
chsahit 1f2526a
fixed most mistakes requested on the PR
chsahit 7dfa79e
more precise URDF and specified in constants.yaml problem with rospar…
chsahit 02fe2fc
added better docs in constants.yaml/steering.py and fixed sim.launch
chsahit 14a9ab9
turns out we don't have to update max_speed in multiple places
chsahit 3f2d0aa
it works now??
chsahit 424d0df
Merge branch 'navsatfix' of https://github.com/gtagency/buzzmobile in…
chsahit 9bf0b1f
bzm now compiles
chsahit 7c0eba0
shrunk the clock down a lot
chsahit 305e67c
added a longer timeout
chsahit File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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"/> | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. YAY CORRECT INERTIALS? There was a problem hiding this comment. Choose a reason for hiding this commentThe 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"/> | ||
|
@@ -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"/> | ||
|
@@ -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> | ||
|
@@ -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"/> | ||
|
@@ -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"/> | ||
|
@@ -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"> | ||
|
@@ -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"> | ||
|
@@ -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> | ||
|
@@ -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> | ||
|
@@ -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> | ||
|
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
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)