Skip to content

Commit

Permalink
v1.9
Browse files Browse the repository at this point in the history
  • Loading branch information
Jonathan Allen committed Nov 3, 2018
1 parent 8f3c7f2 commit f5cd1df
Show file tree
Hide file tree
Showing 11 changed files with 103 additions and 36 deletions.
3 changes: 3 additions & 0 deletions CHANGES.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
# Cepton ROS Release Notes

## Version 1.9 2018-11-02
* Update sdk.

## Version 1.8 2018-10-08
* Updated SDK.

Expand Down
7 changes: 7 additions & 0 deletions third_party/cepton_sdk/include/cepton_sdk.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,13 @@ extern "C" {

#include "cepton_sdk_def.h"

/// API version
#define CEPTON_SDK_VERSION 17

EXPORT const char *cepton_sdk_get_version_string();
EXPORT int cepton_sdk_get_version_major();
EXPORT int cepton_sdk_get_version_minor();

//------------------------------------------------------------------------------
// Errors
//------------------------------------------------------------------------------
Expand Down Expand Up @@ -208,6 +213,8 @@ enum _CeptonSDKControl {
* Does not affect number of points returned.
*/
CEPTON_SDK_CONTROL_ENABLE_STRAY_FILTER = 1 << 5,
/// Always use packet timestamps (disable GPS/PTP timestamps).
CEPTON_SDK_CONTROL_HOST_TIMESTAMPS = 1 << 6,
};

typedef uint32_t CeptonSDKFrameMode;
Expand Down
10 changes: 10 additions & 0 deletions third_party/cepton_sdk/include/cepton_sdk.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,16 @@ namespace cepton_sdk {

#include "cepton_sdk_def.h"

/// Returns library version.
/**
* This is different from `CEPTON_SDK_VERSION`.
*/
inline const char *get_version_string() {
return cepton_sdk_get_version_string();
}
inline int get_version_major() { return cepton_sdk_get_version_major(); }
inline int get_version_minor() { return cepton_sdk_get_version_minor(); }

//------------------------------------------------------------------------------
// Errors
//------------------------------------------------------------------------------
Expand Down
33 changes: 23 additions & 10 deletions third_party/cepton_sdk/include/cepton_sdk_api.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,10 @@ inline SensorError wait(float t_length) {

/// Sleeps or resumes capture replay for duration.
/**
* If `t_length` is `0`, then waits forever.
* If `t_length < 0`, then waits forever.
*/
inline SensorError wait(float t_length = 0.0f) {
if (t_length) {
inline SensorError wait(float t_length = -1.0f) {
if (t_length >= 0.0f) {
return internal::wait(t_length);
} else {
do {
Expand Down Expand Up @@ -149,25 +149,38 @@ inline void default_on_error(SensorHandle h, SensorErrorCode error_code,
// -----------------------------------------------------------------------------
// Setup
// -----------------------------------------------------------------------------
/// Opens capture replay.
inline SensorError open_replay(const std::string &capture_path) {
SensorError error;
if (capture_replay::is_open()) {
error = capture_replay::close();
if (error) return error;
}
error = capture_replay::open(capture_path);
if (error) return error;
error = capture_replay::resume_blocking(10.0f);
if (error) return error;
error = capture_replay::seek(0.0f);
if (error) return error;
return CEPTON_SUCCESS;
}

/// Initialize SDK and optionally starts capture replay.
inline SensorError initialize(Options options = create_options(),
const std::string &capture_path = "") {
const std::string &capture_path = "") {
// Initialize
if (!capture_path.empty())
options.control_flags |= CEPTON_SDK_CONTROL_DISABLE_NETWORK;
util::ErrorAccumulator error =
auto error =
::cepton_sdk::initialize(CEPTON_SDK_VERSION, options, default_on_error);
if (error) return error;

// Open capture replay
if (!capture_path.empty()) {
error = capture_replay::open(capture_path);
error = open_replay(capture_path);
if (error) return error;
}

error = wait(1.0f);
if (!capture_path.empty()) error = capture_replay::seek(0.0f);
return error;
return CEPTON_SUCCESS;
}

inline bool has_control_flags(Control flags) {
Expand Down
86 changes: 60 additions & 26 deletions third_party/cepton_sdk/include/cepton_sdk_util.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ namespace util {
//------------------------------------------------------------------------------
// Common
//------------------------------------------------------------------------------
const int64_t second_usec(1e6);
const int64_t hour_usec(60.0 * 60.0 * 1e6);

inline int64_t to_usec(float sec) { return int64_t(sec * 1e6f); }
inline float from_usec(int64_t usec) { return float(usec) * 1e-6f; }

const int64_t second_usec(to_usec(1.0f));
const int64_t hour_usec(to_usec(60.0f * 60.0f));

template <typename T>
inline T square(T x) {
return x * x;
Expand Down Expand Up @@ -88,36 +88,18 @@ inline void convert_image_point_to_point(float image_x, float image_z,
}

/// 3d point class.
struct SensorPoint {
int64_t timestamp;
struct SensorPoint : public SensorImagePoint {
float x;
float y;
float z;
float intensity;
CeptonSensorReturnType return_type;

#ifdef SIMPLE
uint8_t flags;
#else
union {
uint8_t flags;
struct {
uint8_t valid : 1;
uint8_t saturated : 1;
};
};
uint8_t reserved[2];
#endif
uint8_t reserved;
};

/// Convenience method to convert `CeptonSensorImagePoint` to
/// Convenience method to convert `cepton_sdk::SensorImagePoint` to
/// `cepton_sdk::SensorPoint`.
inline void convert_sensor_image_point_to_point(
const SensorImagePoint &image_point, SensorPoint &point) {
point.timestamp = image_point.timestamp;
point.intensity = image_point.intensity;
point.return_type = image_point.return_type;
point.flags = image_point.flags;
*(SensorImagePoint *)(&point) = image_point;

convert_image_point_to_point(image_point.image_x, image_point.image_z,
image_point.distance, point.x, point.y, point.z);
Expand Down Expand Up @@ -448,6 +430,57 @@ class TimedFrameDetector {
};
} // namespace internal

// Detects scanlines in streaming data.
class ScanlineDetector {
public:
ScanlineDetector(const SensorInformation &sensor_info) {
is_model_supported = true;
m_finder.min_n_after = 2;
reset();
}

void reset() {
scanline_found = false;
m_n = 0;
m_idx_0 = 0;
m_finder.reset();
}

bool add_point(const SensorImagePoint &point) {
scanline_found = false;
scanline_idx = -1;

++m_n;
if (!m_finder.add_value(point.image_z)) return false;

scanline_found = true;
direction = m_finder.direction;
scanline_idx = m_finder.peak_idx + 1;
scanline_z = m_finder.peak_value;

const int idx_0 = m_n - scanline_idx;
scanline_idx += m_idx_0;
m_idx_0 = idx_0;

m_n = 0;
m_finder.reset();
return true;
}

public:
// Outputs
bool is_model_supported;
bool scanline_found;
int direction;
int scanline_idx;
float scanline_z;

private:
int m_n;
int m_idx_0;
internal::PeakFinder m_finder;
};

/// Detects frames in streaming sensor data.
class FrameDetector {
public:
Expand Down Expand Up @@ -545,7 +578,7 @@ class FrameDetector {
break;
default:
assert(false);
return false;
return true;
}

if (frame_idx < 0) {
Expand All @@ -563,6 +596,7 @@ class FrameDetector {
}

public:
// Outputs
bool frame_found;
int frame_idx; /// Number of points in current frame.
float frame_x; /// Sanity check.
Expand Down
Binary file modified third_party/cepton_sdk/lib/linux-aarch64/libcepton_sdk.a
Binary file not shown.
Binary file modified third_party/cepton_sdk/lib/linux-aarch64/libcepton_sdk.so
Binary file not shown.
Binary file modified third_party/cepton_sdk/lib/linux-arm/libcepton_sdk.a
Binary file not shown.
Binary file modified third_party/cepton_sdk/lib/linux-arm/libcepton_sdk.so
Binary file not shown.
Binary file modified third_party/cepton_sdk/lib/linux-x86_64/libcepton_sdk.a
Binary file not shown.
Binary file modified third_party/cepton_sdk/lib/linux-x86_64/libcepton_sdk.so
Binary file not shown.

0 comments on commit f5cd1df

Please sign in to comment.