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

Export compiler directives and some minor changes #144

Open
wants to merge 7 commits into
base: master
Choose a base branch
from
Open
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
5 changes: 5 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package septentrio_gnss_driver
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.4.2 (upcoming)
------------------
* Fixes
* Add export of compiler directives (thanks to @oysstu)

1.4.1 (2024-08-04)
------------------
* Fixes
Expand Down
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ find_package(catkin QUIET)

if(catkin_FOUND)
## ROS 1 -----------------------------------------------------------------------------------------------
add_compile_definitions(ROS1)
set(ENV{ROS_VERSION} "1")

configure_file(${CMAKE_SOURCE_DIR}/msg_cache/BlockHeaderRos1.msg ${CMAKE_SOURCE_DIR}/msg/BlockHeader.msg COPYONLY)
Expand Down Expand Up @@ -129,6 +128,7 @@ if(catkin_FOUND)
${libpcap_LIBRARIES}
${GeographicLib_LIBRARIES}
)
target_compile_definitions(${PROJECT_NAME}_node PUBLIC ROS1)

# Installation
install(TARGETS ${PROJECT_NAME}_node
Expand All @@ -143,7 +143,6 @@ if(catkin_FOUND)
#-------------------------------------------------------------------------------------------------------
elseif(ament_cmake_FOUND)
## ROS 2 -----------------------------------------------------------------------------------------------
add_compile_definitions(ROS2)
set(ENV{ROS_VERSION} "2")

configure_file(${CMAKE_SOURCE_DIR}/msg_cache/BlockHeaderRos2.msg ${CMAKE_SOURCE_DIR}/msg/BlockHeader.msg COPYONLY)
Expand Down Expand Up @@ -231,6 +230,7 @@ elseif(ament_cmake_FOUND)
src/septentrio_gnss_driver/parsers/parsing_utilities.cpp
src/septentrio_gnss_driver/parsers/string_utilities.cpp
)
target_compile_definitions(${library_name} PUBLIC ROS2)
target_include_directories(${library_name} PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>"
Expand All @@ -252,7 +252,7 @@ elseif(ament_cmake_FOUND)
rosidl_get_typesupport_target(
cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
target_link_libraries(${library_name} "${cpp_typesupport_target}")
add_compile_definitions(ROS2_VER_N250)
target_compile_definitions(${library_name} PUBLIC ROS2_VER_N250)
endif()

## executable
Expand Down
1 change: 1 addition & 0 deletions include/septentrio_gnss_driver/abstraction/typedefs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,7 @@ typedef geometry_msgs::msg::Quaternion QuaternionMsg;
typedef geometry_msgs::msg::PoseWithCovarianceStamped PoseWithCovarianceStampedMsg;
typedef geometry_msgs::msg::TwistWithCovarianceStamped TwistWithCovarianceStampedMsg;
typedef geometry_msgs::msg::TransformStamped TransformStampedMsg;
typedef geometry_msgs::msg::Vector3 Vector3Msg;
typedef gps_msgs::msg::GPSFix GpsFixMsg;
typedef gps_msgs::msg::GPSStatus GpsStatusMsg;
typedef sensor_msgs::msg::NavSatFix NavSatFixMsg;
Expand Down
4 changes: 3 additions & 1 deletion include/septentrio_gnss_driver/abstraction/typedefs_ros1.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,7 @@ typedef geometry_msgs::Quaternion QuaternionMsg;
typedef geometry_msgs::PoseWithCovarianceStamped PoseWithCovarianceStampedMsg;
typedef geometry_msgs::TwistWithCovarianceStamped TwistWithCovarianceStampedMsg;
typedef geometry_msgs::TransformStamped TransformStampedMsg;
typedef geometry_msgs::Vector3 Vector3Msg;
typedef gps_common::GPSFix GpsFixMsg;
typedef gps_common::GPSStatus GpsStatusMsg;
typedef sensor_msgs::NavSatFix NavSatFixMsg;
Expand Down Expand Up @@ -186,7 +187,8 @@ class ROSaicNodeBase
{
public:
ROSaicNodeBase() :
pNh_(new ros::NodeHandle("~")), tfListener_(tfBuffer_), lastTfStamp_(0)
pNh_(std::make_shared<ros::NodeHandle>("~")), tfListener_(tfBuffer_),
lastTfStamp_(0)
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ namespace io {
template <typename IoType>
AsyncManager<IoType>::AsyncManager(ROSaicNodeBase* node,
TelegramQueue* telegramQueue) :
node_(node), ioService_(new boost::asio::io_service),
node_(node), ioService_(std::make_shared<boost::asio::io_service>()),
ioInterface_(node, ioService_), telegramQueue_(telegramQueue)
{
node_->log(log_level::DEBUG, "AsyncManager created.");
Expand Down Expand Up @@ -305,7 +305,7 @@ namespace io {
template <typename IoType>
void AsyncManager<IoType>::resync()
{
telegram_.reset(new Telegram);
telegram_ = std::make_shared<Telegram>();
readSync<0>();
}

Expand Down Expand Up @@ -589,7 +589,7 @@ namespace io {
{
case SYNC_BYTE_1:
{
telegram_.reset(new Telegram);
telegram_ = std::make_shared<Telegram>();
telegram_->message[0] = buf_[0];
telegram_->stamp = node_->getTime();
node_->log(
Expand Down
18 changes: 9 additions & 9 deletions include/septentrio_gnss_driver/communication/io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,9 +88,9 @@ namespace io {
private:
void connect()
{
socket_.reset(new boost::asio::ip::udp::socket(
socket_ = std::make_unique<boost::asio::ip::udp::socket>(
ioService_,
boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(), port_)));
boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(), port_));

asyncReceive();

Expand Down Expand Up @@ -120,7 +120,7 @@ namespace io {
{
while ((bytes_recvd - idx) > 2)
{
std::shared_ptr<Telegram> telegram(new Telegram);
auto telegram = std::make_shared<Telegram>();
telegram->stamp = stamp;
/*node_->log(log_level::DEBUG,
"Buffer: " + std::string(telegram->message.begin(),
Expand Down Expand Up @@ -283,7 +283,7 @@ namespace io {
return false;
}

stream_.reset(new boost::asio::ip::tcp::socket(*ioService_));
stream_ = std::make_unique<boost::asio::ip::tcp::socket>(*ioService_);

node_->log(log_level::INFO, "Connecting to tcp://" +
node_->settings()->device_tcp_ip + ":" +
Expand Down Expand Up @@ -372,7 +372,7 @@ namespace io {
flowcontrol_(node->settings()->hw_flow_control),
baudrate_(node->settings()->baudrate)
{
stream_.reset(new boost::asio::serial_port(*ioService_));
stream_ = std::make_unique<boost::asio::serial_port>(*ioService_);
}

~SerialIo() { stream_->close(); }
Expand Down Expand Up @@ -582,8 +582,8 @@ namespace io {

try
{
stream_.reset(
new boost::asio::posix::stream_descriptor(*ioService_));
stream_ = std::make_unique<boost::asio::posix::stream_descriptor>(
*ioService_);
stream_->assign(fd);

} catch (std::runtime_error& e)
Expand Down Expand Up @@ -631,8 +631,8 @@ namespace io {
node_->log(log_level::INFO, "Opening pcap file stream" +
node_->settings()->device + "...");

stream_.reset(
new boost::asio::posix::stream_descriptor(*ioService_));
stream_ = std::make_unique<boost::asio::posix::stream_descriptor>(
*ioService_);

pcap_ = pcap_open_offline(node_->settings()->device.c_str(),
errBuff_.data());
Expand Down
Loading