Skip to content
Merged
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
7 changes: 6 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,11 @@ set(CMAKE_POSITION_INDEPENDENT_CODE ON)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Werror)

# ignore the private-field-unused warning with clang
if(CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wno-unused-private-field)
endif()
endif()

find_package(rclcpp REQUIRED)
Expand All @@ -51,7 +56,7 @@ endif()
add_library(driver SHARED src/libcaer_wrapper.cpp src/driver.cpp
src/message_converter.cpp
src/device/device.cpp src/device/davis.cpp src/device/dvxplorer.cpp)
target_include_directories(driver PUBLIC include)
target_include_directories(driver PUBLIC include include/device)
target_link_libraries(driver ${rclcpp_components_TARGETS}
${event_camera_msgs_TARGETS} ${sensor_msgs_TARGETS}
${std_srvs_TARGETS} libcaer::caer rclcpp::rclcpp
Expand Down
5 changes: 2 additions & 3 deletions include/libcaer_driver/callback_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,8 @@ class CallbackHandler
virtual void deviceDisconnectedCallback() = 0;
virtual void polarityPacketCallback(
uint64_t t, const libcaer::events::PolarityEventPacket & packet) = 0;
virtual void framePacketCallback(
uint64_t t, const libcaer::events::FrameEventPacket & packet) = 0;
virtual void imu6PacketCallback(uint64_t t, const libcaer::events::IMU6EventPacket & packet) = 0;
virtual void framePacketCallback(const libcaer::events::FrameEventPacket & packet) = 0;
virtual void imu6PacketCallback(const libcaer::events::IMU6EventPacket & packet) = 0;
};
} // namespace libcaer_driver
#endif // LIBCAER_DRIVER__CALLBACK_HANDLER_HPP_
4 changes: 2 additions & 2 deletions include/libcaer_driver/driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,8 @@ class Driver : public rclcpp::Node, public CallbackHandler
void deviceDisconnectedCallback() override;
void polarityPacketCallback(
uint64_t t, const libcaer::events::PolarityEventPacket & packet) override;
void framePacketCallback(uint64_t t, const libcaer::events::FrameEventPacket & packet) override;
void imu6PacketCallback(uint64_t t, const libcaer::events::IMU6EventPacket & packet) override;
void framePacketCallback(const libcaer::events::FrameEventPacket & packet) override;
void imu6PacketCallback(const libcaer::events::IMU6EventPacket & packet) override;

// ---------------- end of inherited -----------

Expand Down
1 change: 1 addition & 0 deletions launch/driver_composition.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ def launch_setup(context, *args, **kwargs):
"aps_frame_mode": 1,
"auto_exposure_enabled": False,
"auto_exposure_illumination": 127.0,
"time_reset_delay": 0, # increase for syncing mult. cameras
},
],
extra_arguments=[{"use_intra_process_comms": True}],
Expand Down
5 changes: 4 additions & 1 deletion launch/start_recording.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,10 @@ def launch_setup(context, *args, **kwargs):
name='recorder',
parameters=[
{
'record.topics': ['/event_camera/events'],
'record.topics': [
'/event_camera/events',
'/event_camera/imu',
],
# 'record.topics': ['/event_camera/events',
# '/event_camera/image_raw'],
'record.start_paused': False,
Expand Down
10 changes: 4 additions & 6 deletions src/driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -535,12 +535,11 @@ static int32_t compute_new_exposure_time(
return (newTime);
}

void Driver::framePacketCallback(uint64_t t, const libcaer::events::FrameEventPacket & packet)
void Driver::framePacketCallback(const libcaer::events::FrameEventPacket & packet)
{
if (cameraPub_.getNumSubscribers() > 0) {
std::vector<std::unique_ptr<sensor_msgs::msg::Image>> msgs;
(void)message_converter::convert_frame_packet(
&msgs, packet, cameraFrameId_, rclcpp::Time(t, RCL_SYSTEM_TIME));
(void)message_converter::convert_frame_packet(&msgs, packet, cameraFrameId_, rosBaseTime_);
for (auto & img : msgs) {
sensor_msgs::msg::CameraInfo::UniquePtr cinfo(
new sensor_msgs::msg::CameraInfo(cameraInfoMsg_));
Expand All @@ -567,12 +566,11 @@ void Driver::framePacketCallback(uint64_t t, const libcaer::events::FrameEventPa
}
}

void Driver::imu6PacketCallback(uint64_t t, const libcaer::events::IMU6EventPacket & packet)
void Driver::imu6PacketCallback(const libcaer::events::IMU6EventPacket & packet)
{
if (imuPub_->get_subscription_count() > 0) {
std::vector<std::unique_ptr<sensor_msgs::msg::Imu>> msgs;
(void)message_converter::convert_imu6_packet(
&msgs, packet, imuFrameId_, rclcpp::Time(t, RCL_SYSTEM_TIME));
(void)message_converter::convert_imu6_packet(&msgs, packet, imuFrameId_, rosBaseTime_);
for (auto & msg : msgs) {
imuPub_->publish(std::move(msg));
}
Expand Down
4 changes: 2 additions & 2 deletions src/libcaer_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,12 +205,12 @@ void LibcaerWrapper::processPacket(
}
case FRAME_EVENT: {
const auto & fpacket = static_cast<const libcaer::events::FrameEventPacket &>(packet);
callbackHandler_->framePacketCallback(nsSinceEpoch, fpacket);
callbackHandler_->framePacketCallback(fpacket);
break;
}
case IMU6_EVENT: {
const auto & fpacket = static_cast<const libcaer::events::IMU6EventPacket &>(packet);
callbackHandler_->imu6PacketCallback(nsSinceEpoch, fpacket);
callbackHandler_->imu6PacketCallback(fpacket);
break;
}
default:
Expand Down