Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
F
Firmware
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Package registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Terms and privacy
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Alberto Ruiz Garcia
Firmware
Commits
97d31f66
Commit
97d31f66
authored
10 years ago
by
Marcel Stüttgen
Browse files
Options
Downloads
Patches
Plain Diff
modified default pwm values and added comments to the startup scripts
parent
6d1df8f7
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
ROMFS/px4fmu_common/init.d/50001_rover
+2
-2
2 additions, 2 deletions
ROMFS/px4fmu_common/init.d/50001_rover
ROMFS/px4fmu_common/init.d/rc.rover_defaults
+17
-7
17 additions, 7 deletions
ROMFS/px4fmu_common/init.d/rc.rover_defaults
with
19 additions
and
9 deletions
ROMFS/px4fmu_common/init.d/50001_rover
+
2
−
2
View file @
97d31f66
...
...
@@ -3,8 +3,8 @@
# Generic rover
#
#load some defaults e.g. PWM values
sh /etc/init.d/rc.rover_defaults
#choose a mixer, for rover control we need a plain passthrough to the servos
set MIXER IO_pass
set PWM_OUT 1234
This diff is collapsed.
Click to expand it.
ROMFS/px4fmu_common/init.d/rc.rover_defaults
+
17
−
7
View file @
97d31f66
...
...
@@ -2,12 +2,22 @@
set VEHICLE_TYPE rover
if [ $AUTOCNF == yes ]
then
# param set MC_ROLL_P 7.0
fi
# i dont think AUTOCNF is needed here, can it be removed?
#if [ $AUTOCNF == yes ]
#then
# # param set MC_ROLL_P 7.0
#fi
#PWM Hz
set PWM_RATE 50
set PWM_DISARMED 1100
set PWM_MIN 1100
set PWM_MAX 1900
#PWW default value for "disarmed" mode
set PWM_DISARMED 1500
#PWM range
set PWM_MIN 1200
set PWM_MAX 1800
#enable servo output on pins 3 and 4 (steering and thrust)
set PWM_OUT 34
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment