Skip to content

Commit

Permalink
chote: rebased and fixed rebse-related errors
Browse files Browse the repository at this point in the history
Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp>
  • Loading branch information
knzo25 committed May 27, 2024
1 parent f2ad48e commit f8bea9a
Show file tree
Hide file tree
Showing 18 changed files with 217 additions and 71 deletions.
2 changes: 1 addition & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ repos:
args: [--markdown-linebreak-ext=md]

- repo: https://github.com/igorshubovych/markdownlint-cli
rev: v0.40.0
rev: v0.41.0
hooks:
- id: markdownlint
args: [-c, .markdownlint.yaml, --fix]
Expand Down
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,7 @@ Supported models, where sensor_model is the ROS param to be used at launch:
| Velodyne | VLP-32 | VLP32 | VLP32.yaml | :warning: |
| Velodyne | VLS-128 | VLS128 | VLS128.yaml | :warning: |
| Continental | ARS548 | ARS548 | ARS548.yaml | :warning: |
| Continental | SRR520 | SRR520 | SRR520.yaml | :warning: |

Test status:\
:heavy_check_mark:: complete\
Expand Down
4 changes: 4 additions & 0 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,7 @@ repositories:
type: git
url: https://github.com/mojomex/transport_drivers
version: mutable-buffer-in-udp-callback
ros2_socketcan:
type: git
url: https://github.com/knzo25/ros2_socketcan
version: feat/continental_fd
81 changes: 63 additions & 18 deletions nebula_common/include/nebula_common/nebula_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,7 @@
#define NEBULA_COMMON_H

#include <nebula_common/point_types.hpp>

#include <boost/tokenizer.hpp>

#include <algorithm>
#include <map>
#include <ostream>
#include <string>
Expand Down Expand Up @@ -327,9 +324,11 @@ enum class SensorModel {
VELODYNE_HDL32,
VELODYNE_VLP16,
ROBOSENSE_HELIOS,
ROBOSENSE_BPEARL,
ROBOSENSE_BPEARL_V3,
ROBOSENSE_BPEARL_V4,
CONTINENTAL_ARS548
CONTINENTAL_ARS548,
CONTINENTAL_SRR520
};

/// @brief not used?
Expand All @@ -344,11 +343,24 @@ enum class datatype {
FLOAT64 = 8
};

enum class PtpProfile { IEEE_1588v2 = 0, IEEE_802_1AS, IEEE_802_1AS_AUTO, UNKNOWN_PROFILE };
enum class PtpProfile {
IEEE_1588v2 = 0,
IEEE_802_1AS,
IEEE_802_1AS_AUTO,
UNKNOWN_PROFILE
};

enum class PtpTransportType { UDP_IP = 0, L2, UNKNOWN_TRANSPORT };
enum class PtpTransportType {
UDP_IP = 0,
L2,
UNKNOWN_TRANSPORT
};

enum class PtpSwitchType { NON_TSN = 0, TSN, UNKNOWN_SWITCH };
enum class PtpSwitchType {
NON_TSN = 0,
TSN,
UNKNOWN_SWITCH
};

/// @brief not used?
struct PointField
Expand Down Expand Up @@ -417,6 +429,9 @@ inline std::ostream & operator<<(std::ostream & os, nebula::drivers::SensorModel
case SensorModel::ROBOSENSE_HELIOS:
os << "HELIOS";
break;
case SensorModel::ROBOSENSE_BPEARL:
os << "BPEARL";
break;
case SensorModel::ROBOSENSE_BPEARL_V3:
os << "BPEARL V3.0";
break;
Expand All @@ -426,6 +441,9 @@ inline std::ostream & operator<<(std::ostream & os, nebula::drivers::SensorModel
case SensorModel::CONTINENTAL_ARS548:
os << "ARS548";
break;
case SensorModel::CONTINENTAL_SRR520:
os << "SRR520";
break;
case SensorModel::UNKNOWN:
os << "Sensor Unknown";
break;
Expand All @@ -448,6 +466,16 @@ struct EthernetSensorConfigurationBase : SensorConfigurationBase
uint16_t data_port;
};

/// @brief Base struct for CAN-based Sensor configuration
struct CANSensorConfigurationBase : SensorConfigurationBase
{
std::string interface;
float receiver_timeout_sec{};
float sender_timeout_sec{};
std::string filters{};
bool use_bus_time{};
};

/// @brief Base struct for Lidar configuration
struct LidarConfigurationBase : EthernetSensorConfigurationBase
{
Expand Down Expand Up @@ -483,6 +511,19 @@ inline std::ostream & operator<<(std::ostream & os, EthernetSensorConfigurationB
return os;
}

/// @brief Convert CANSensorConfigurationBase to string (Overloading the << operator)
/// @param os
/// @param arg
/// @return stream
inline std::ostream & operator<<(std::ostream & os, CANSensorConfigurationBase const & arg)
{
os << (SensorConfigurationBase)(arg)
<< ", Interface: " << arg.interface << ", ReceiverTimeoutSec: " << arg.receiver_timeout_sec
<< ", SenderTimeoutSec: " << arg.sender_timeout_sec << ", Filters: " << arg.filters
<< ", UseBusTime: " << arg.use_bus_time;
return os;
}

/// @brief Convert LidarConfigurationBase to string (Overloading the << operator)
/// @param os
/// @param arg
Expand Down Expand Up @@ -526,10 +567,12 @@ inline SensorModel SensorModelFromString(const std::string & sensor_model)
if (sensor_model == "VLP16") return SensorModel::VELODYNE_VLP16;
// Robosense
if (sensor_model == "Helios") return SensorModel::ROBOSENSE_HELIOS;
if (sensor_model == "Bpearl" || sensor_model == "Bpearl_V4")
return SensorModel::ROBOSENSE_BPEARL_V4;
if (sensor_model == "Bpearl") return SensorModel::ROBOSENSE_BPEARL;
if (sensor_model == "Bpearl_V3") return SensorModel::ROBOSENSE_BPEARL_V3;
if (sensor_model == "Bpearl_V4") return SensorModel::ROBOSENSE_BPEARL_V4;
// Continental
if (sensor_model == "ARS548") return SensorModel::CONTINENTAL_ARS548;
if (sensor_model == "SRR520") return SensorModel::CONTINENTAL_SRR520;
return SensorModel::UNKNOWN;
}

Expand Down Expand Up @@ -571,12 +614,17 @@ inline std::string SensorModelToString(const SensorModel & sensor_model)
// Robosense
case SensorModel::ROBOSENSE_HELIOS:
return "Helios";
case SensorModel::ROBOSENSE_BPEARL:
return "Bpearl";
case SensorModel::ROBOSENSE_BPEARL_V3:
return "Bpearl_V3";
case SensorModel::ROBOSENSE_BPEARL_V4:
return "Bpearl_V4";
// Continental
case SensorModel::CONTINENTAL_ARS548:
return "ARS548";
case SensorModel::CONTINENTAL_SRR520:
return "SRR520";
default:
return "UNKNOWN";
}
Expand All @@ -602,9 +650,8 @@ inline PtpProfile PtpProfileFromString(const std::string & ptp_profile)
{
// Hesai
auto tmp_str = ptp_profile;
std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), [](unsigned char c) {
return std::tolower(c);
});
std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(),
[](unsigned char c){ return std::tolower(c); });
if (tmp_str == "1588v2") return PtpProfile::IEEE_1588v2;
if (tmp_str == "802.1as") return PtpProfile::IEEE_802_1AS;
if (tmp_str == "automotive") return PtpProfile::IEEE_802_1AS_AUTO;
Expand Down Expand Up @@ -642,9 +689,8 @@ inline PtpTransportType PtpTransportTypeFromString(const std::string & transport
{
// Hesai
auto tmp_str = transport_type;
std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), [](unsigned char c) {
return std::tolower(c);
});
std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(),
[](unsigned char c){ return std::tolower(c); });
if (tmp_str == "udp") return PtpTransportType::UDP_IP;
if (tmp_str == "l2") return PtpTransportType::L2;

Expand Down Expand Up @@ -678,9 +724,8 @@ inline PtpSwitchType PtpSwitchTypeFromString(const std::string & switch_type)
{
// Hesai
auto tmp_str = switch_type;
std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), [](unsigned char c) {
return std::tolower(c);
});
std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(),
[](unsigned char c){ return std::tolower(c); });
if (tmp_str == "tsn") return PtpSwitchType::TSN;
if (tmp_str == "non_tsn") return PtpSwitchType::NON_TSN;

Expand Down
15 changes: 15 additions & 0 deletions nebula_common/include/nebula_common/nebula_status.hpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
// Copyright 2024 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NEBULA_STATUS_HPP
#define NEBULA_STATUS_HPP

Expand All @@ -14,6 +28,7 @@ struct Status
enum Type {
OK = 0,
UDP_CONNECTION_ERROR,
CAN_CONNECTION_ERROR,
SENSOR_CONFIG_ERROR,
INVALID_SENSOR_MODEL,
INVALID_ECHO_MODE,
Expand Down
1 change: 1 addition & 0 deletions nebula_decoders/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ ament_auto_add_library(nebula_decoders_robosense_info SHARED
# Continental
ament_auto_add_library(nebula_decoders_continental SHARED
src/nebula_decoders_continental/decoders/continental_ars548_decoder.cpp
src/nebula_decoders_continental/decoders/continental_srr520_decoder.cpp
)

if(BUILD_TESTING)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,21 +51,6 @@ class ContinentalArs548Decoder : public ContinentalPacketsDecoder
/// @return Resulting flag
bool ProcessPacket(std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg) override;

/// @brief Function for parsing detection lists
/// @param data
/// @return Resulting flag
bool ParseDetectionsListPacket(std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg);

/// @brief Function for parsing object lists
/// @param data
/// @return Resulting flag
bool ParseObjectsListPacket(std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg);

/// @brief Function for parsing sensor status messages
/// @param data
/// @return Resulting flag
bool ParseSensorStatusPacket(std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg);

/// @brief Register function to call when a new detection list is processed
/// @param detection_list_callback
/// @return Resulting status
Expand Down Expand Up @@ -111,10 +96,10 @@ class ContinentalArs548Decoder : public ContinentalPacketsDecoder
std::function<void(std::unique_ptr<continental_msgs::msg::ContinentalArs548DetectionList> msg)>
detection_list_callback_{};
std::function<void(std::unique_ptr<continental_msgs::msg::ContinentalArs548ObjectList> msg)>
object_list_callback_;
std::function<void(const ContinentalArs548Status & status)> sensor_status_callback_;
object_list_callback_{};
std::function<void(const ContinentalArs548Status & status)> sensor_status_callback_{};
std::function<void(std::unique_ptr<nebula_msgs::msg::NebulaPackets> msg)>
nebula_packets_callback_;
nebula_packets_callback_{};

ContinentalArs548Status radar_status_{};

Expand Down
Loading

0 comments on commit f8bea9a

Please sign in to comment.