Skip to content

Commit

Permalink
Merge branch 'main' into pr/ike-kazu/180
Browse files Browse the repository at this point in the history
  • Loading branch information
mojomex committed Aug 14, 2024
2 parents ff6d867 + d9aaefc commit f92849a
Show file tree
Hide file tree
Showing 10 changed files with 33 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -620,7 +620,7 @@ struct FilterStatusPacket

#pragma pack(pop)

struct PointARS548Detection
struct EIGEN_ALIGN16 PointARS548Detection
{
PCL_ADD_POINT4D;
float azimuth;
Expand All @@ -639,11 +639,11 @@ struct PointARS548Detection
uint16_t object_id;
uint8_t ambiguity_flag;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
};

// Note we only use a subset of the data since POINT_CLOUD_REGISTER_POINT_STRUCT has a limit in the
// number of fields
struct PointARS548Object
struct EIGEN_ALIGN16 PointARS548Object
{
PCL_ADD_POINT4D;
uint32_t id;
Expand All @@ -664,7 +664,7 @@ struct PointARS548Object
float shape_width_edge_mean;
float dynamics_orientation_rate_mean;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
};

} // namespace continental_ars548
} // namespace drivers
Expand Down
8 changes: 4 additions & 4 deletions nebula_common/include/nebula_common/point_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@ namespace nebula
{
namespace drivers
{
struct PointXYZIR
struct EIGEN_ALIGN16 PointXYZIR
{
PCL_ADD_POINT4D;
float intensity;
uint16_t ring;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
};

struct PointXYZICATR
{
Expand Down Expand Up @@ -43,7 +43,7 @@ struct PointXYZIRCAEDT
std::uint32_t time_stamp;
};

struct PointXYZIRADT
struct EIGEN_ALIGN16 PointXYZIRADT
{
PCL_ADD_POINT4D;
float intensity;
Expand All @@ -53,7 +53,7 @@ struct PointXYZIRADT
uint8_t return_type;
double time_stamp;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
};

using NebulaPoint = PointXYZIRCAEDT;
using NebulaPointPtr = std::shared_ptr<NebulaPoint>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -578,6 +578,14 @@ Status ContinentalARS548HwInterface::SetYawRate(float yaw_rate)
return Status::OK;
}

Status ContinentalARS548HwInterface::CheckAndSetConfig()
{
RCLCPP_ERROR(
*parent_node_logger,
"This functionality is not yet implemented. Sensor is probably out of sync with config now.");
return Status::ERROR_1;
}

void ContinentalARS548HwInterface::SetLogger(std::shared_ptr<rclcpp::Logger> logger)
{
parent_node_logger = logger;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -406,6 +406,14 @@ Status MultiContinentalARS548HwInterface::SetYawRate(float yaw_rate)
return Status::OK;
}

Status MultiContinentalARS548HwInterface::CheckAndSetConfig()
{
RCLCPP_ERROR(
*parent_node_logger,
"This functionality is not yet implemented. Sensor is probably out of sync with config now.");
return Status::ERROR_1;
}

void MultiContinentalARS548HwInterface::SetLogger(std::shared_ptr<rclcpp::Logger> logger)
{
parent_node_logger = logger;
Expand Down
2 changes: 1 addition & 1 deletion nebula_messages/nebula_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<license>Apache 2</license>
<author>Tier IV</author>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<depend>builtin_interfaces</depend>
Expand Down
Binary file not shown.
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,15 @@ rosbag2_bagfile_information:
version: 5
storage_identifier: sqlite3
duration:
nanoseconds: 277624032
nanoseconds: 263164997
starting_time:
nanoseconds_since_epoch: 1614315746471294674
nanoseconds_since_epoch: 1585897255313147068
message_count: 4
topics_with_message_count:
- topic_metadata:
name: /sensing/lidar/top/velodyne_packets
name: /velodyne_packets
type: velodyne_msgs/msg/VelodyneScan
serialization_format: cdr
serialization_format: ""
offered_qos_profiles: ""
message_count: 4
compression_format: ""
Expand All @@ -20,7 +20,7 @@ rosbag2_bagfile_information:
files:
- path: 1614315746471294674_0.db3
starting_time:
nanoseconds_since_epoch: 1614315746471294674
nanoseconds_since_epoch: 1585897255313147068
duration:
nanoseconds: 277624032
message_count: 4
nanoseconds: 263164997
message_count: 4
Binary file not shown.
3 changes: 1 addition & 2 deletions nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ Status VelodyneRosDecoderTest::GetParameters(
descriptor.dynamic_typing = false;
descriptor.additional_constraints = "";
this->declare_parameter<std::string>(
"target_topic", "/sensing/lidar/top/velodyne_packets", descriptor);
"target_topic", "/velodyne_packets", descriptor);
target_topic = this->get_parameter("target_topic").as_string();
}

Expand Down Expand Up @@ -315,7 +315,6 @@ void VelodyneRosDecoderTest::ReadBag()

storage_options.uri = bag_path;
storage_options.storage_id = storage_id;
converter_options.output_serialization_format = format; //"cdr";
rclcpp::Serialization<velodyne_msgs::msg::VelodyneScan> serialization;
nebula::drivers::NebulaPointCloudPtr pointcloud(new nebula::drivers::NebulaPointCloud);
// nebula::drivers::NebulaPointCloudPtr ref_pointcloud(new nebula::drivers::NebulaPointCloud);
Expand Down

0 comments on commit f92849a

Please sign in to comment.