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

Feature/ulanding #4

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
Open

Feature/ulanding #4

wants to merge 6 commits into from

Conversation

rikba
Copy link
Contributor

@rikba rikba commented Dec 11, 2019

Builds up on #3 (merge first).

This PR introduces a u landing altimeter sensor into the VersaVis repository.

  • uLanding class attached to timer
  • Uses same timer as CAM2 by default. User can now disable CAM2 and enable uLanding.
  • Serial connection can be specified
  • Minimum launch example

@rikba
Copy link
Contributor Author

rikba commented Dec 11, 2019

Tested on Rev1.1

header: 
  seq: 189
  stamp: 
    secs: 196555153
    nsecs: 194552000
  frame_id: "u_landing"
radiation_type: 2
field_of_view: 0.5
min_range: 0.34999999404
max_range: 45.0
range: 1.75

@floriantschopp floriantschopp self-requested a review August 8, 2020 14:31
Copy link
Contributor

@floriantschopp floriantschopp left a comment

Choose a reason for hiding this comment

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

Mostly the same comments as in #3 and requires #3 to be merged first.
Thanks a lot for the addition!

@@ -0,0 +1,82 @@
#include "LidarLite.h"
Copy link
Contributor

Choose a reason for hiding this comment

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

Reviewed in #3

@@ -0,0 +1,44 @@
////////////////////////////////////////////////////////////////////////////////
Copy link
Contributor

Choose a reason for hiding this comment

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

Reviewed in #3

@@ -43,6 +43,27 @@ Sensor::Sensor(ros::NodeHandle *nh, const String &topic, const int rate_hz,
}
}

// Range message version.
Copy link
Contributor

Choose a reason for hiding this comment

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

Reviewed in #3

@@ -17,6 +17,7 @@
#include "Timer.h"
#include <ros.h>
#include <versavis/ImuMicro.h>
#include <versavis/RangeMicro.h>
Copy link
Contributor

Choose a reason for hiding this comment

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

Reviewed in #3.

@@ -0,0 +1,135 @@
////////////////////////////////////////////////////////////////////////////////
Copy link
Contributor

Choose a reason for hiding this comment

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

Reviewed in #3

Comment on lines +11 to +13
if (uart_)
uart_->begin(115200);

Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
if (uart_)
uart_->begin(115200);
if (uart_) {
uart_->begin(115200);
}

// On Arduino the Serial buffer automatically fills up with incoming data
// until the buffer is full. The best timestamp we can set is now, to
// stamp the next arriving sample after the buffer has been emptied.
Sensor::setTimestampNow();
Copy link
Contributor

Choose a reason for hiding this comment

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

Are you sure that the data that you read in line 51 corresponds to the previous call of the function?

@@ -0,0 +1,104 @@
#include "ULanding.h"
Copy link
Contributor

Choose a reason for hiding this comment

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

In general the same comments apply as in #3, LidarLite.cpp

Comment on lines +258 to +268
#ifdef USE_CAM2
void TC3_Handler() { // Called by cam2_timer for camera 2 trigger.
cam2.triggerMeasurement();
}
#endif

#ifdef USE_U_LANDING
void TC3_Handler() { // Called by u_landing_timer for uLanding trigger.
u_landing.triggerMeasurement();
}
#endif
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
#ifdef USE_CAM2
void TC3_Handler() { // Called by cam2_timer for camera 2 trigger.
cam2.triggerMeasurement();
}
#endif
#ifdef USE_U_LANDING
void TC3_Handler() { // Called by u_landing_timer for uLanding trigger.
u_landing.triggerMeasurement();
}
#endif
void TC3_Handler() { // Called by cam2_timer for camera 2 trigger or by u_landing_timer for uLanding trigger.
#ifdef USE_CAM2
cam2.triggerMeasurement();
#endif
#ifdef USE_U_LANDING
u_landing.triggerMeasurement();
#endif
}

@@ -135,7 +176,7 @@ void setup() {
; // wait for sync
}

// Enable TC4 (not used) and TC5 timers.
// Enable TC4 (LidarLite) and TC5 timers.
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
// Enable TC4 (LidarLite) and TC5 timers.
// Enable TC4 (LidarLite) and TC5 (IMU) timers.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants