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

AP_Proximity: add support for RP Lidar A2 (360° Lidar with upto 16m range) #6552

Closed

Conversation

amilcarlucas
Copy link
Contributor

No description provided.

@OXINARF
Copy link
Member

OXINARF commented Jul 9, 2017

@amilcarlucas Is this ready for review? It's marked as WIP...

@amilcarlucas
Copy link
Contributor Author

We are still going to do small changes to it, so please wait a while longer before reviewing.

@khancyr
Copy link
Contributor

khancyr commented Aug 17, 2017

@amilcarlucas ping !

@amilcarlucas
Copy link
Contributor Author

This is ready for review since 11 July.
Is there anything I can do ?

@khancyr
Copy link
Contributor

khancyr commented Aug 17, 2017

it doesn't pass travis, can you look at it ?

@amilcarlucas
Copy link
Contributor Author

amilcarlucas commented Aug 17, 2017

@SteveJos Can you please take a look at it ?

@amilcarlucas amilcarlucas force-pushed the pr-rp-lidar-a2-support branch from b509678 to 93d5b02 Compare August 21, 2017 09:14
@amilcarlucas
Copy link
Contributor Author

This fixed the tests on our local CI server. Let's see how Travis-CI likes it :)

@OXINARF
Copy link
Member

OXINARF commented Aug 21, 2017

@amilcarlucas

This is ready for review since 11 July.

You didn't write anything, we can't guess 🙂

This fixed the tests on our local CI server. Let's see how Travis-CI likes it :)

Well, it doesn't even build... You need to rebase on master and fix the issues.

@amilcarlucas amilcarlucas force-pushed the pr-rp-lidar-a2-support branch from 93d5b02 to e850728 Compare August 21, 2017 12:14
@amilcarlucas
Copy link
Contributor Author

Rebased on master and fixed the build

@amilcarlucas amilcarlucas force-pushed the pr-rp-lidar-a2-support branch from e850728 to 6e1aaed Compare August 24, 2017 16:12
Copy link
Member

@OXINARF OXINARF left a comment

Choose a reason for hiding this comment

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

I've made some inline comments. I have to say the driver looks way more complicated than it needed to be, but if it works, that's fine.

All the checks for RP_LIDAR_DEBUG are terrible, you should do something similar to a lot of other drivers:

#if RPI_LIDAR_DEBUG
  #include <GCS_MAVLINK/GCS.h>
  #define Debug(level, fmt, args ...)  do { if (level <= RPI_LIDAR_DEBUG) { GCS_MAVLINK::send_text(MAV_SEVERITY_INFO, fmt, ## args); } } while (0)
#else
  #define Debug(level, fmt, args ...)
#endif

And then just call Debug(1, "LIDAR IS OK - state: %s", state_string).

AP_SerialManager &serial_manager) :
AP_Proximity_Backend(_frontend, _state)
{
_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0); // selected in MP at SerialConfig
Copy link
Member

Choose a reason for hiding this comment

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

Comment at end of line should be removed

extern const AP_HAL::HAL& hal;

/*
The constructor also initialises the proximity sensor. Note that this
Copy link
Member

Choose a reason for hiding this comment

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

Doesn't look like this is true, probably a left-over from earlier code?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The SF40 codes does the same, the comment must be fixed in there as well


// initialise sensor if necessary
if(!_initialised)
{
Copy link
Member

Choose a reason for hiding this comment

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

Wrong formatting

#define RPLIDAR_CMD_GET_DEVICE_HEALTH 0x52

// Commands with payload and have response
#define RPLIDAR_CMD_EXPRESS_SCAN 0x82
Copy link
Member

Choose a reason for hiding this comment

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

All macros above should be moved to cpp file.

#include "AP_Proximity.h"
#include "AP_Proximity_Backend.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_Common/AP_Common.h> ///< using overloaded uart->write() function for transmitting HEX bytes
Copy link
Member

Choose a reason for hiding this comment

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

Last two includes seem not needed, AP_HAL.h is though (for UARTDriver).

}

// initialise sector angles using user defined ignore areas, left same as SF40C
// TODO: adapt to RPLIDAR A2 measurements
Copy link
Member

Choose a reason for hiding this comment

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

What is this TODO?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

This function is a 1:1 copy of AP_Proximity_LightWareSF40C::init_sectors().

Copy link
Contributor

@rmackay9 rmackay9 Sep 16, 2017

Choose a reason for hiding this comment

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

I think we can remove this To-Do. The To-Do itself isn't in the SF40C version.
We should probably move this to the backend to remove the duplication..

uint8_t ignore_area_count = get_ignore_area_count();
if (ignore_area_count == 0) {
_sector_initialised = true;
return;
Copy link
Member

Choose a reason for hiding this comment

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

This looks wrong. What about _num_sectors and init_boundary()? In this case, the for loop below wouldn't do anything, so why is a special check needed for it?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Again that is the same code as AP_Proximity_LightWareSF40C.cpp
That again needs to be fixed in there as well.

Copy link
Contributor

Choose a reason for hiding this comment

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

we need the special check so that if the "ignore_area_count" is zero, we leave the _num_sectors and _boundary array at their defaults which is 8 sectors of 45degrees each. Without the special check the _num_sectors would be set to zero.

GCS_MAVLINK::send_text(MAV_SEVERITY_INFO, " CURRENT STATE: %d ", _rp_state);
#endif
uint32_t nbytes = _uart->available();
static uint16_t byte_count = 0;
Copy link
Member

Choose a reason for hiding this comment

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

Put this in the class, no need for static.

if (convert_angle_to_sector(angle_deg, sector)) {
_angle[sector] = angle_deg;
_distance[sector] = distance_m;
_distance_valid[sector] = true;
Copy link
Member

Choose a reason for hiding this comment

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

There's no check for distance being 0 and so invalid.


// reply related variables
AP_HAL::UARTDriver *_uart;
// char element_buf[2][10];
Copy link
Member

Choose a reason for hiding this comment

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

Don't leave dead code.

@amilcarlucas
Copy link
Contributor Author

We improved it a bit more and will push more comits soon.

@amilcarlucas amilcarlucas force-pushed the pr-rp-lidar-a2-support branch from 26dac40 to 002aa96 Compare September 3, 2017 15:25
@amilcarlucas
Copy link
Contributor Author

@OXINARF I think we have addressed all of your points. The missing ones need to be addressed by @rmackay9 because he is the author of the original SF40 code and the issues you raise are SF40 issues as well.

@amilcarlucas amilcarlucas force-pushed the pr-rp-lidar-a2-support branch from 002aa96 to 0808c51 Compare September 4, 2017 08:43
@rmackay9 rmackay9 removed the WIP label Sep 4, 2017
@rmackay9 rmackay9 assigned rmackay9 and unassigned rmackay9 Sep 4, 2017
_uart->write(tx_buffer, 2);
_resetted = true; ///< be aware of extra 63 bytes coming after reset containing FW information
Debug(1, "LIDAR reset");
hal.scheduler->delay(RESET_RPA2_WAIT_MS); ///< wait at least 8ms after sending new request
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Any Ideas on How to improve and or avoid this hal.scheduler->delay(RESET_RPA2_WAIT_MS); call ?

@rmackay9
Copy link
Contributor

I've made some formatting changes, squashed the commits and removed the killer delay (and added a To-Do in it's place) and pushed into master. Thanks!

@rmackay9 rmackay9 closed this Sep 17, 2017
@amilcarlucas amilcarlucas deleted the pr-rp-lidar-a2-support branch September 18, 2017 09:36
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants