-
Notifications
You must be signed in to change notification settings - Fork 40
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
Enable user defined IMU Parameters from JSBSim #24
Merged
Merged
Changes from all commits
Commits
Show all changes
8 commits
Select commit
Hold shift + click to select a range
7a86536
Add px4_default_imu_sensor.xml
mvacanti 8085246
Include mapping to JSBSim IMU parameters.
mvacanti 429e06f
Include system file mapping for px4_default_imu_sensor
mvacanti dff7d9b
Enable XML mapping of JSBSim parameters
mvacanti 729dfea
Move default values of JSBSim properties
mvacanti 84a1d64
Merge branch 'master' of https://github.com/Auterion/px4-jsbsim-bridg…
mvacanti 53f41fd
Minor comment change
mvacanti 02df55c
Naming convention update
mvacanti 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
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 |
---|---|---|
@@ -0,0 +1,161 @@ | ||
<?xml version="1.0"?> | ||
<system name="PX4 IMU Sensor"> | ||
<!-- ================================================================= | ||
This is a generic JSBSim system file to simulate the IMU behavior for PX4. | ||
================================================================= --> | ||
|
||
<!-- Enable Individual Component Failure --> | ||
<property value="1">px4/acc_x/on</property> | ||
<property value="1">px4/acc_y/on</property> | ||
<property value="1">px4/acc_z/on</property> | ||
|
||
<property value="1">px4/gyro_x/on</property> | ||
<property value="1">px4/gyro_y/on</property> | ||
<property value="1">px4/gyro_z/on</property> | ||
|
||
<channel name="Accelerometer-X" execute="px4/acc_x/on"> | ||
<accelerometer name="Default-ACC-X"> | ||
<location unit="M"> | ||
<x> 0 </x> | ||
<y> 0 </y> | ||
<z> 0.345 </z> | ||
</location> | ||
<!-- | ||
<orientation unit="DEG"> | ||
<pitch> 0 </pitch> | ||
<roll> 0 </roll> | ||
<yaw> 0 </yaw> | ||
</orientation> | ||
<lag> 0 </lag> | ||
<noise variation="PERCENT|ABSOLUTE"> number </noise> | ||
<quantization name="name"> | ||
<bits> number </bits> | ||
<min> number </min> | ||
<max> number </max> | ||
</quantization> | ||
<drift_rate> number </drift_rate> | ||
<gain> number </gain> | ||
<bias> number </bias> | ||
--> | ||
<axis> X </axis> | ||
<output> px4/acc-x </output> | ||
</accelerometer> | ||
</channel> | ||
|
||
<channel name="Accelerometer-Y" execute="px4/acc_y/on"> | ||
<accelerometer name="Default-ACC-Y"> | ||
<location unit="M"> | ||
<x> 0 </x> | ||
<y> 0 </y> | ||
<z> 0.345 </z> | ||
</location> | ||
<!-- | ||
<orientation unit="DEG"> | ||
<pitch> 0 </pitch> | ||
<roll> 0 </roll> | ||
<yaw> 0 </yaw> | ||
</orientation> | ||
<lag> 0 </lag> | ||
<noise variation="PERCENT|ABSOLUTE"> number </noise> | ||
<quantization name="name"> | ||
<bits> number </bits> | ||
<min> number </min> | ||
<max> number </max> | ||
</quantization> | ||
<drift_rate> number </drift_rate> | ||
<gain> number </gain> | ||
<bias> number </bias> | ||
--> | ||
<axis> Y </axis> | ||
<output> px4/acc-y </output> | ||
</accelerometer> | ||
</channel> | ||
|
||
<channel name="Accelerometer-Z" execute="px4/acc_z/on"> | ||
<accelerometer name="Default-ACC-Z"> | ||
<location unit="M"> | ||
<x> 0 </x> | ||
<y> 0 </y> | ||
<z> 0.345 </z> | ||
</location> | ||
<!-- | ||
<orientation unit="DEG"> | ||
<pitch> 0 </pitch> | ||
<roll> 0 </roll> | ||
<yaw> 0 </yaw> | ||
</orientation> | ||
<lag> 0 </lag> | ||
<noise variation="PERCENT|ABSOLUTE"> number </noise> | ||
<quantization name="name"> | ||
<bits> number </bits> | ||
<min> number </min> | ||
<max> number </max> | ||
</quantization> | ||
<drift_rate> number </drift_rate> | ||
<gain> number </gain> | ||
<bias> number </bias> | ||
--> | ||
<axis> Z </axis> | ||
<output> px4/acc-z </output> | ||
</accelerometer> | ||
</channel> | ||
|
||
<channel name="Gyro-X" execute="px4/gyro_x/on"> | ||
<sensor name="px4/gyro-x"> | ||
<input>velocities/p-rad_sec</input> | ||
<lag> 0 </lag> | ||
<!--Adjust as required | ||
<noise variation="PERCENT|ABSOLUTE"> number </noise> | ||
<quantization name="name"> | ||
<bits> number </bits> | ||
<min> number </min> | ||
<max> number </max> | ||
</quantization> | ||
<drift_rate> number </drift_rate> | ||
<gain> number </gain> | ||
<bias> number </bias> | ||
<delay [type="time|frames"]> number < /delay> | ||
--> | ||
</sensor> | ||
</channel> | ||
|
||
<channel name="Gyro-Y" execute="px4/gyro_y/on"> | ||
<sensor name="px4/gyro-y"> | ||
<input>velocities/q-rad_sec</input> | ||
<lag> 0 </lag> | ||
<!--Adjust as required | ||
<noise variation="PERCENT|ABSOLUTE"> number </noise> | ||
<quantization name="name"> | ||
<bits> number </bits> | ||
<min> number </min> | ||
<max> number </max> | ||
</quantization> | ||
<drift_rate> number </drift_rate> | ||
<gain> number </gain> | ||
<bias> number </bias> | ||
<delay [type="time|frames"]> number < /delay> | ||
--> | ||
</sensor> | ||
</channel> | ||
|
||
<channel name="Gyro-Z" execute="px4/gyro_z/on"> | ||
<sensor name="px4/gyro-z"> | ||
<input>velocities/r-rad_sec</input> | ||
<lag> 0 </lag> | ||
<!--Adjust as required | ||
<noise variation="PERCENT|ABSOLUTE"> number </noise> | ||
<quantization name="name"> | ||
<bits> number </bits> | ||
<min> number </min> | ||
<max> number </max> | ||
</quantization> | ||
<drift_rate> number </drift_rate> | ||
<gain> number </gain> | ||
<bias> number </bias> | ||
<delay [type="time|frames"]> number < /delay> | ||
--> | ||
</sensor> | ||
</channel> | ||
|
||
</system> | ||
|
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.
Is there a way to avoid duplicating this for the other axes?
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 believe this is a constraint of the JSBSim accelerometer function. There are a few functions that allow XML variables to be passed so that you could accomplish something like this where the property is declared once:
I dug into the backend of JSBSim (and tried a few combination of the above) and unfortunately the only input it accepts are numeric.
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.
Ok, let's keep it as is then.