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

feat: support innovusion lidar falcon and robin #87

Closed
wants to merge 14 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 38 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,8 @@ Supported models, where sensor_model is the ROS param to be used at launch:
| Velodyne | VLP-16-HiRes | VLP16 | | :x: |
| Velodyne | VLP-32 | VLP32 | VLP32.yaml | :warning: |
| Velodyne | VLS-128 | VLS128 | VLS128.yaml | :warning: |
| Innovusion | Falcon | Falcon | Falcon.yaml | :warning: |
| Innovusion | Robin | Robin | Robin.yaml | :warning: |

Test status:\
:heavy_check_mark:: complete\
Expand Down Expand Up @@ -222,6 +224,42 @@ Parameters shared by all supported models:
| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle |
| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle |

### Innovusion specific parameters

#### Supported return modes

| return_mode | Mode |
| --------------- | ------------------ |
| SingleFirst | Single (First) |
| SingleStrongest | Single (Strongest) |
| SingleLast | Single (Last) |
| Dual | Dual |

#### Hardware interface parameters

| Parameter | Type | Default | Accepted values | Description |
| --------------- | ------ | --------------- | ----------------- | --------------- |
| frame_id | string | innovusion | | ROS frame ID |
| sensor_ip | string | 172.168.1.11 | | Sensor IP |
| host_ip | string | 255.255.255.255 | | Host IP |
| data_port | uint16 | 8010 | | Sensor port |
| gnss_port | uint16 | 8010 | | GNSS port |
| frequency_ms | uint16 | 100 | milliseconds, > 0 | Time per scan |
| packet_mtu_size | uint16 | 8820 | | Packet MTU size |
| cloud_min_angle | uint16 | 0 | degrees [0, 120] | FoV start angle |
| cloud_max_angle | uint16 | 120 | degrees [0, 120] | FoV end angle |

#### Driver parameters

| Parameter | Type | Default | Accepted values | Description |
| ---------------- | ------ | -------- | -------------------- | ------------------------------------- |
| frame_id | string | innovusion | | ROS frame ID |
| calibration_file | string | | | LiDAR calibration file |
| min_range | double | 0.3 | meters, >= 0.3 | Minimum point range published |
| max_range | double | 500.0 | meters, <= 500.0 | Maximum point range published |
| cloud_min_angle | uint16 | 0 | degrees [0, 120] | FoV start angle |
| cloud_max_angle | uint16 | 120 | degrees [0, 120] | FoV end angle

## Software design overview

![DriverOrganization](docs/diagram.png)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
#ifndef NEBULA_INNOVUSION_COMMON_H
#define NEBULA_INNOVUSION_COMMON_H

#include "nebula_common/nebula_common.hpp"
#include "nebula_common/nebula_status.hpp"

#include <fstream>
#include <sstream>
namespace nebula
{
namespace drivers
{
/// @brief struct for Innovusion sensor configuration
struct InnovusionSensorConfiguration : SensorConfigurationBase
{
uint16_t reserved_1;
};
/// @brief Convert InnovusionSensorConfiguration to string (Overloading the << operator)
/// @param os
/// @param arg
/// @return stream
inline std::ostream & operator<<(std::ostream & os, InnovusionSensorConfiguration const & arg)
{
os << (SensorConfigurationBase)(arg);
return os;
}

/// @brief struct for Innovusion calibration configuration
struct InnovusionCalibrationConfiguration : CalibrationConfigurationBase
{
// InnovusionCalibration innovusion_calibration;
inline nebula::Status LoadFromFile(const std::string & calibration_file)
{
return Status::OK;
}
inline nebula::Status SaveFile(const std::string & calibration_file)
{
return Status::OK;
}
};

/// @brief Convert return mode name to ReturnMode enum (Innovusion-specific ReturnModeFromString)
/// @param return_mode Return mode name (Upper and lower case letters must match)
/// @return Corresponding ReturnMode
inline ReturnMode ReturnModeFromStringInnovusion(const std::string & return_mode)
{
if (return_mode == "Strongest") return ReturnMode::SINGLE_STRONGEST;
if (return_mode == "Last") return ReturnMode::SINGLE_LAST;
if (return_mode == "Dual") return ReturnMode::DUAL_ONLY;

return ReturnMode::UNKNOWN;
}

} // namespace drivers
} // namespace nebula

#endif // NEBULA_INNOVUSION_COMMON_H
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
#ifndef Innovusion_STATUS_HPP
#define Innovusion_STATUS_HPP

#include "nebula_common/nebula_status.hpp"

#include <ostream>
#include <string>

namespace nebula
{
// from https://marycore.jp/prog/cpp/extends-enum/

/// @brief Status definition for Innovusion
struct InnovusionStatus : Status
{
using Status::Status;

private:
int _type_num;

public:
enum InnovusionType {
INVALID_RPM_ERROR = Type_end_of_Status + 1,
INVALID_FOV_ERROR,
INVALID_RETURN_MODE_ERROR,
Type_end_of_Status = INVALID_RPM_ERROR
} _Innovusion_type;
InnovusionStatus() : _type_num(static_cast<int>(Status::OK)) { _type = static_cast<Type>(type()); }
InnovusionStatus(Type v) : _type_num(static_cast<int>(v)) { _type = v; }
InnovusionStatus(InnovusionType v) : _type_num(static_cast<int>(v)), _Innovusion_type(v)
{
_type = Type::Type_end_of_Status;
}
InnovusionStatus(int type) : _type_num(type) {}
int type() const { return _type_num; }
friend bool operator==(const InnovusionStatus & L, const InnovusionStatus & R)
{
return L.type() == R.type();
}
friend bool operator!=(const InnovusionStatus & L, const InnovusionStatus & R)
{
return L.type() != R.type();
}

/// @brief Convert Status enum to string (Overloading the << operator)
/// @param os
/// @param arg
/// @return stream
friend std::ostream & operator<<(std::ostream & os, nebula::InnovusionStatus const & arg)
{
switch (arg.type()) {
// Velodyne
case InnovusionStatus::INVALID_RPM_ERROR:
os << "Invalid rotation speed value(range from 300 to 1200, in increments of 60)";
break;
case InnovusionStatus::INVALID_FOV_ERROR:
os << "Invalid fov value(0 to 359)";
break;
case InnovusionStatus::INVALID_RETURN_MODE_ERROR:
os << "Invalid return mode(only SINGLE_STRONGEST, SINGLE_LAST, DUAL_ONLY)";
break;
default:
os << Status(arg._type);
}
return os;
}
};
} // namespace nebula
#endif // Innovusion_STATUS_HPP
11 changes: 11 additions & 0 deletions nebula_common/include/nebula_common/nebula_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,6 +323,8 @@ enum class SensorModel {
VELODYNE_VLP32MR,
VELODYNE_HDL32,
VELODYNE_VLP16,
INNOVUSION_FALCON,
INNOVUSION_ROBIN
};

/// @brief not used?
Expand Down Expand Up @@ -401,6 +403,12 @@ inline std::ostream & operator<<(std::ostream & os, nebula::drivers::SensorModel
case SensorModel::VELODYNE_VLP16:
os << "VLP16";
break;
case SensorModel::INNOVUSION_FALCON:
os << "Falcon";
break;
case SensorModel::INNOVUSION_ROBIN:
os << "Robin";
break;
case SensorModel::UNKNOWN:
os << "Sensor Unknown";
break;
Expand Down Expand Up @@ -468,6 +476,9 @@ inline SensorModel SensorModelFromString(const std::string & sensor_model)
if (sensor_model == "VLP32MR") return SensorModel::VELODYNE_VLP32MR;
if (sensor_model == "HDL32") return SensorModel::VELODYNE_HDL32;
if (sensor_model == "VLP16") return SensorModel::VELODYNE_VLP16;
// innovusion
if (sensor_model == "Falcon") return SensorModel::INNOVUSION_FALCON;
if (sensor_model == "Robin") return SensorModel::INNOVUSION_ROBIN;
return SensorModel::UNKNOWN;
}

Expand Down
6 changes: 6 additions & 0 deletions nebula_decoders/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,12 @@ ament_auto_add_library(nebula_decoders_velodyne SHARED
src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp
)

# Innovusion
ament_auto_add_library(nebula_decoders_innovusion SHARED
src/nebula_decoders_innovusion/decoders/innovusion_decoder.cpp
src/nebula_decoders_innovusion/innovusion_driver.cpp
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
4 changes: 4 additions & 0 deletions nebula_decoders/calibration/innovusion/Falcon.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Our Lidar is calibrated internally, so there is no need to use calibration files here.
# However, in order to maintain consistency in the Nebula framework, we created an empty calibration file.
# Please ignore it.
yaml_version: 2023110701
4 changes: 4 additions & 0 deletions nebula_decoders/calibration/innovusion/Robin.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Our Lidar is calibrated internally, so there is no need to use calibration files here.
# However, in order to maintain consistency in the Nebula framework, we created an empty calibration file.
# Please ignore it.
yaml_version: 2023110701
Loading