* Creating a base for grf lidar * Serial Drive is working, need to work out distance publish * WIP Getting Range Data in cm * Working Rand Distance Values for GRF 250 and GRF500 * Review Changes * Compiler fixes * Update to date * small update * Fix typo and remover unused libs * removing unused enum * Update to the Documentation * Fiving scaling issue * update to the logic * [Feature] Adding I2C driver for the GRF250 and GRF500 models (#26425) * Adding the GRF I2C driver * I2C Driver Working * Removing a lot of unnecessary code * fixing names * Changing the i2c Driver to be in the lightware laser * remove the old driver * formatting fix * Adding Ligthware GRF to documentation * Update to the Documentation * Ensuring sample_perf ends * Updating Docs * uavcannode: implement hardpoint commands (#26334) * implement cannode hardpoint commands Signed-off-by: dirksavage88 <dirksavage88@gmail.com> * Update src/drivers/uavcannode/Subscribers/HardpointCommand.hpp Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> * Update src/drivers/uavcannode/Subscribers/HardpointCommand.hpp Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> * add hardpoint sub to ark cannode, simplify handling of hardpoint broadcast Signed-off-by: dirksavage88 <dirksavage88@gmail.com> --------- Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> * voxl_esc: Limit frequency of UART passthru writes to 20Hz * voxl2_io: Added UART passthru * docs: update link for px4 ros2 interface lib python api docs * estimator_interface: remove unused getter * gnss_checks: always run strict checks on ground With the goal to never take off if the GNSS solution is not fullfilling the configured requirements still not stopping to use it in case it degrades mid air. * ekf2 unit-tests: adapt to strict GNSS checks on ground * escCheck: rework online check to properly report offline ESCs previous to this 09d79b221f274523349a029e63ab4462e41d0c1c set `esc_online_flags` e.g. for UAVCAN ESCs which specific one is online and that then got compared to a mask where the first `esc_count` bits were set. So if only ESC 5 is mapped and online you get the message "ESC 156 offline" because `esc_online_flags = 0b1000` gets compared to `online_bitmask = 0b1` based on `esc_count = 1` and the motor index is `esc[0].actuator_function = 0` wrapped using `0 - actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1 + 1 = 156`. * FailureDetector: consistent timestamp naming * FailureDetector: rework motor status check * FailureDetector: implement upper and lower current limit with offset * Update src/modules/commander/failure_detector/FailureDetector.cpp Prevent Buffer overflow * Update Format * Subedit * Shrink and rename image * Apply suggestion from @hamishwillee Sounds good Co-authored-by: Hamish Willee <hamishwillee@gmail.com> * Apply suggestion from @hamishwillee More universal approach Co-authored-by: Hamish Willee <hamishwillee@gmail.com> * Update to the Documentation * FailureDetector: rework motor status check * FailureDetector: implement upper and lower current limit with offset * Subedit * docs: update parameter reference metadata * Remove pregenerated files - that should all be tidied up next time this runs * remover GRF parameters * Documentation updates * Fixing Merge Conflicts * remove @ * Undo Changes to parameter_reference * remove the code that will be autogen-ed * Update the Camake File --------- Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Co-authored-by: Andrew Brahim <35986980+dirksavage88@users.noreply.github.com> Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Co-authored-by: Eric Katzfey <eric.katzfey@modalai.com> Co-authored-by: Beat Küng <beat-kueng@gmx.net> Co-authored-by: Matthias Grob <maetugr@gmail.com> Co-authored-by: Marco Hauswirth <marco.hauswirth@auterion.com> Co-authored-by: Nick <145654544+ttechnick@users.noreply.github.com> Co-authored-by: Hamish Willee <hamishwillee@gmail.com> Co-authored-by: Ramon Roche <mrpollo@gmail.com>
4.0 KiB
Lightware GRF250/GRF500 Gimbal Lidar
LightWare GRF250 and GRF500 are small and light Lidar modules with a range of 250m and 500m, respectively.
::: info The Lidar driver is not included in the default build of PX4. You will need to create and use a custom build. :::
Where to Buy
Order these modules from:
Hardware Setup
The rangefinder can be connected to any unused serial port, such as TELEM2.
Parameter Configuration explains how to configure the port to use and the other properties of the rangefinder.
PX4 Setup
Add the Driver to the PX4 Build
The lightware_grf_serial driver for this Lidar is not included in PX4 firmware by default. In order to use these modules you will first need to update the firmware configuration to add the driver, and then build the firmware.
-
Update the firmware configuration. You can use either of the following options:
-
Menuconfig:
- Install and open menuconfig
- In menuconfig, navigate to Drivers > Distance sensors
- Select/Enable
lightware_grf_serial - Save the configuration
-
Manually update
default.px4to include the configuration key:-
Open the
default.px4boardconfig file that corresponds to the board you want to build for. For example, to add the driver tofmu-v6xboards you would update /boards/px4/fmu-v6x/default.px4board -
Add the following line and save the file:
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_GRF_SERIAL=y
-
-
-
Build PX4 for your flight controller target and upload the new firmware.
Parameter Configuration
You will need to configure PX4 to indicate the serial port to which the sensor is connected (as per Serial Port Configuration) and also the orientation and other properties of the sensor.
The parameters to change are listed in the table.
| Parameter | Description |
|---|---|
| SENS_EN_GRF_CFG | Set to the serial port the sensor is connected to. |
| GRF_UPDATE_CFG | Set the update rate. |
| GRF_SENS_MODEL | Set the update rate. |
Testing
You can confirm that the sensor is correctly configured by connecting QGroundControl, and observing that DISTANCE_SENSOR is present in the MAVLink Inspector.
Moving the sensor around at various distances from a surface will have the current_distance value change.
Troubleshooting
If you are having problems with connecting to the sensor you may need to unassign a the default serial port. Unassign Default Serial Port
