Skip to content

Commit

Permalink
Managed to change the Max Distance Detection. Needs further debugging
Browse files Browse the repository at this point in the history
  • Loading branch information
ferfercal99 committed Jun 26, 2024
1 parent 3e56828 commit 1fb9b70
Show file tree
Hide file tree
Showing 4 changed files with 365 additions and 162 deletions.
2 changes: 1 addition & 1 deletion ars548_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ find_package(ars548_messages REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)

include_directories(include)

add_executable(ars548_driver src/ars548_driver_node.cpp)
ament_target_dependencies(ars548_driver rclcpp ars548_messages sensor_msgs tf2_geometry_msgs)
Expand Down
1 change: 1 addition & 0 deletions ars548_driver/include/ars548_driver/ars548_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
* It is also used to fill the messages sent to the user.
* @brief Data obtained from the RadarSensors_Annex_AES548_IO SW 05.48.04.pdf
*/
#pragma once
#include <cstdint>
#pragma pack(1)
struct UDPStatus {
Expand Down
2 changes: 1 addition & 1 deletion ars548_driver/include/ars548_driver/ars548_driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -663,7 +663,7 @@ class ars548_driver : public rclcpp::Node{
/**
*
*/
static bool receiveStatusMsg(int nbytes,const char * buffer,struct UDPStatus& status){
static bool receiveStatusMsg(int nbytes,const char * buffer, UDPStatus &status){
if(nbytes==STATUS_MESSAGE_PAYLOAD)
{
status = *((struct UDPStatus *)buffer);
Expand Down
Loading

0 comments on commit 1fb9b70

Please sign in to comment.