diff --git a/mvsim_node_src/include/mvsim/mvsim_node_core.h b/mvsim_node_src/include/mvsim/mvsim_node_core.h index a96e9e72..3d8e93cf 100644 --- a/mvsim_node_src/include/mvsim/mvsim_node_core.h +++ b/mvsim_node_src/include/mvsim/mvsim_node_core.h @@ -9,9 +9,6 @@ #pragma once -#include -#include - #include #include #include @@ -25,20 +22,21 @@ #include #include -#if PACKAGE_ROS_VERSION == 1 -#include -#include +#include +#include +#if PACKAGE_ROS_VERSION == 1 #include -#include - #include #include #include #include +#include +#include #include #include -#include +#include +#include #include #include #include @@ -59,17 +57,16 @@ using Msg_Bool = std_msgs::Bool; using Msg_TFMessage = tf2_msgs::TFMessage; using Msg_MarkerArray = visualization_msgs::MarkerArray; #else -#include -#include -#include - #include #include #include #include +#include #include #include -#include +#include +#include +#include #include #include @@ -81,7 +78,8 @@ using ros_Duration = rclcpp::Duration; using Msg_Polygon = geometry_msgs::msg::Polygon; using Msg_PoseArray = geometry_msgs::msg::PoseArray; -using Msg_PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; +using Msg_PoseWithCovarianceStamped = + geometry_msgs::msg::PoseWithCovarianceStamped; using Msg_Twist = geometry_msgs::msg::Twist; using Msg_Twist_CSPtr = geometry_msgs::msg::Twist::ConstSharedPtr; using Msg_OccupancyGrid = nav_msgs::msg::OccupancyGrid; @@ -92,25 +90,28 @@ using Msg_TFMessage = tf2_msgs::msg::TFMessage; using Msg_MarkerArray = visualization_msgs::msg::MarkerArray; #endif -namespace mvsim_node { +namespace mvsim_node +{ #if PACKAGE_ROS_VERSION == 1 - template - boost::shared_ptr make_shared(Args&&... args) { - return boost::make_shared(std::forward(args)...); - } +template +boost::shared_ptr make_shared(Args&&... args) +{ + return boost::make_shared(std::forward(args)...); +} - template - using shared_ptr = boost::shared_ptr; +template +using shared_ptr = boost::shared_ptr; #else - template - std::shared_ptr make_shared(Args&&... args) { - return std::make_shared(std::forward(args)...); - } +template +std::shared_ptr make_shared(Args&&... args) +{ + return std::make_shared(std::forward(args)...); +} - template - using shared_ptr = std::shared_ptr; +template +using shared_ptr = std::shared_ptr; #endif -} +} // namespace mvsim_node /** A class to wrap libmvsim as a ROS node */ @@ -198,23 +199,33 @@ class MVSimNode struct TPubSubPerVehicle { #if PACKAGE_ROS_VERSION == 1 - mvsim_node::shared_ptr sub_cmd_vel; //!< Subscribers vehicle's "cmd_vel" topic - mvsim_node::shared_ptr pub_odom; //!< Publisher of "odom" topic - mvsim_node::shared_ptr pub_ground_truth; //!< "base_pose_ground_truth" topic + mvsim_node::shared_ptr + sub_cmd_vel; //!< Subscribers vehicle's "cmd_vel" topic + mvsim_node::shared_ptr + pub_odom; //!< Publisher of "odom" topic + mvsim_node::shared_ptr + pub_ground_truth; //!< "base_pose_ground_truth" topic /// "fake_localization" pubs: - mvsim_node::shared_ptr pub_amcl_pose; //!< Publisher of "amcl_pose" topic - mvsim_node::shared_ptr pub_particlecloud; //!< Publisher of "particlecloud" topic + mvsim_node::shared_ptr + pub_amcl_pose; //!< Publisher of "amcl_pose" topic + mvsim_node::shared_ptr + pub_particlecloud; //!< Publisher of "particlecloud" topic /// Map => publisher - std::map> pub_sensors; + std::map> + pub_sensors; - mvsim_node::shared_ptr pub_chassis_markers; //!< "/chassis_markers" - mvsim_node::shared_ptr pub_chassis_shape; //!< "/chassis_shape" - mvsim_node::shared_ptr pub_collision; //!< "/collision" + mvsim_node::shared_ptr + pub_chassis_markers; //!< "/chassis_markers" + mvsim_node::shared_ptr + pub_chassis_shape; //!< "/chassis_shape" + mvsim_node::shared_ptr + pub_collision; //!< "/collision" - mvsim_node::shared_ptr pub_tf; //!< "/tf" - mvsim_node::shared_ptr pub_tf_static; //!< "/tf_static" + mvsim_node::shared_ptr pub_tf; //!< "/tf" + mvsim_node::shared_ptr + pub_tf_static; //!< "/tf_static" Msg_MarkerArray chassis_shape_msg; #else @@ -226,20 +237,18 @@ class MVSimNode rclcpp::Publisher::SharedPtr pub_ground_truth; /// "fake_localization" pubs: - rclcpp::Publisher:: - SharedPtr pub_amcl_pose; - rclcpp::Publisher::SharedPtr - pub_particlecloud; + rclcpp::Publisher::SharedPtr + pub_amcl_pose; + rclcpp::Publisher::SharedPtr pub_particlecloud; /// Map => publisher - std::map> pub_sensors; + std::map> + pub_sensors; /// "/chassis_markers" - rclcpp::Publisher::SharedPtr - pub_chassis_markers; + rclcpp::Publisher::SharedPtr pub_chassis_markers; /// "/chassis_shape" - rclcpp::Publisher::SharedPtr - pub_chassis_shape; + rclcpp::Publisher::SharedPtr pub_chassis_shape; /// "/collision" rclcpp::Publisher::SharedPtr pub_collision; @@ -263,9 +272,7 @@ class MVSimNode // === End ROS Publishers ==== // === ROS Hooks ==== - void onROSMsgCmdVel( - Msg_Twist_CSPtr cmd, - mvsim::VehicleBase* veh); + void onROSMsgCmdVel(Msg_Twist_CSPtr cmd, mvsim::VehicleBase* veh); // === End ROS Hooks==== #if PACKAGE_ROS_VERSION == 1 @@ -328,9 +335,7 @@ class MVSimNode void sendStaticTF( const std::string& frame_id, const std::string& child_frame_id, - const tf2::Transform& tx, - const ros_Time& stamp - ); + const tf2::Transform& tx, const ros_Time& stamp); ros_Time myNow() const; double myNowSec() const; diff --git a/mvsim_node_src/include/wrapper/publisher_wrapper.h b/mvsim_node_src/include/wrapper/publisher_wrapper.h index c7471f74..fa850da6 100644 --- a/mvsim_node_src/include/wrapper/publisher_wrapper.h +++ b/mvsim_node_src/include/wrapper/publisher_wrapper.h @@ -5,31 +5,41 @@ #include "rclcpp/rclcpp.hpp" -class PublisherWrapperBase { - public: - PublisherWrapperBase() = default; - virtual ~PublisherWrapperBase() = default; - virtual void publish(std::shared_ptr message) = 0; +class PublisherWrapperBase +{ + public: + PublisherWrapperBase() = default; + virtual ~PublisherWrapperBase() = default; + virtual void publish(std::shared_ptr message) = 0; }; - template -class PublisherWrapper : public PublisherWrapperBase { - public: - PublisherWrapper(rclcpp::Node::SharedPtr node, const std::string& topic_name, size_t qos) - : publisher_(node->create_publisher(topic_name, qos)) {} - - void publish(std::shared_ptr msg) override { - const auto typed_msg = std::static_pointer_cast(msg); - if (typed_msg) { - publisher_->publish(*typed_msg); - } else { - RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to cast message to correct type."); - } - } - - private: - typename rclcpp::Publisher::SharedPtr publisher_; +class PublisherWrapper : public PublisherWrapperBase +{ + public: + PublisherWrapper( + rclcpp::Node::SharedPtr node, const std::string& topic_name, size_t qos) + : publisher_(node->create_publisher(topic_name, qos)) + { + } + + void publish(std::shared_ptr msg) override + { + const auto typed_msg = std::static_pointer_cast(msg); + if (typed_msg) + { + publisher_->publish(*typed_msg); + } + else + { + RCLCPP_ERROR( + rclcpp::get_logger("rclcpp"), + "Failed to cast message to correct type."); + } + } + + private: + typename rclcpp::Publisher::SharedPtr publisher_; }; #endif diff --git a/mvsim_node_src/mvsim_node.cpp b/mvsim_node_src/mvsim_node.cpp index b5ece193..1cff1a80 100644 --- a/mvsim_node_src/mvsim_node.cpp +++ b/mvsim_node_src/mvsim_node.cpp @@ -34,7 +34,6 @@ #include #include #include - #include #include #include @@ -107,8 +106,10 @@ namespace mrpt2ros = mrpt::ros2bridge; #define ROS12_ERROR(...) ROS_ERROR(__VA_ARGS__) #else #define ROS12_INFO(...) RCLCPP_INFO(n_->get_logger(), __VA_ARGS__) -#define ROS12_WARN_THROTTLE(...) RCLCPP_WARN_THROTTLE(n_->get_logger(), *clock_, __VA_ARGS__) -#define ROS12_WARN_STREAM_THROTTLE(...) RCLCPP_WARN_STREAM_THROTTLE(n_->get_logger(), *clock_, __VA_ARGS__) +#define ROS12_WARN_THROTTLE(...) \ + RCLCPP_WARN_THROTTLE(n_->get_logger(), *clock_, __VA_ARGS__) +#define ROS12_WARN_STREAM_THROTTLE(...) \ + RCLCPP_WARN_STREAM_THROTTLE(n_->get_logger(), *clock_, __VA_ARGS__) #define ROS12_ERROR(...) RCLCPP_ERROR(n_->get_logger(), __VA_ARGS__) #endif @@ -193,21 +194,25 @@ MVSimNode::MVSimNode(rclcpp::Node::SharedPtr& n) // Init ROS publishers: #if PACKAGE_ROS_VERSION == 1 - // pub_clock_ = mvsim_node::make_shared(n_.advertise("/clock", 10)); - - pub_map_ros_ = mvsim_node::make_shared(n_.advertise( - "simul_map", 1 /*queue len*/, true /*latch*/)); - pub_map_metadata_ = mvsim_node::make_shared(n_.advertise( - "simul_map_metadata", 1 /*queue len*/, true /*latch*/)); + // pub_clock_ = + // mvsim_node::make_shared(n_.advertise("/clock", + // 10)); + + pub_map_ros_ = + mvsim_node::make_shared(n_.advertise( + "simul_map", 1 /*queue len*/, true /*latch*/)); + pub_map_metadata_ = + mvsim_node::make_shared(n_.advertise( + "simul_map_metadata", 1 /*queue len*/, true /*latch*/)); #else rclcpp::QoS qosLatched(rclcpp::KeepLast(10)); qosLatched.durability( rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); - pub_map_ros_ = n_->create_publisher( - "simul_map", qosLatched); - pub_map_metadata_ = n_->create_publisher( - "simul_map_metadata", qosLatched); + pub_map_ros_ = + n_->create_publisher("simul_map", qosLatched); + pub_map_metadata_ = + n_->create_publisher("simul_map_metadata", qosLatched); #endif #if PACKAGE_ROS_VERSION == 1 @@ -398,8 +403,7 @@ void MVSimNode::spin() // Generic teleoperation interface for any controller that // supports it: { - auto* controller = - it_veh->second->getControllerInterface(); + auto* controller = it_veh->second->getControllerInterface(); ControllerBaseInterface::TeleopInput teleop_in; ControllerBaseInterface::TeleopOutput teleop_out; teleop_in.keycode = keyevent.keycode; @@ -417,15 +421,14 @@ void MVSimNode::spin() } // end refresh teleop stuff -// Check cmd_vel timeout: + // Check cmd_vel timeout: const double rosNow = myNowSec(); std::set toRemove; for (const auto& [veh, cmdVelTimestamp] : lastCmdVelTimestamp_) { if (rosNow - cmdVelTimestamp > MAX_CMD_VEL_AGE_SECONDS) { - auto* controller = - veh->getControllerInterface(); + auto* controller = veh->getControllerInterface(); controller->setTwistCommand({0, 0, 0}); toRemove.insert(veh); @@ -565,7 +568,8 @@ void MVSimNode::notifyROSWorldIsUpdated() // sendStaticTF("world", "map", tfIdentity_, myNow()); } -ros_Time MVSimNode::myNow() const { +ros_Time MVSimNode::myNow() const +{ #if PACKAGE_ROS_VERSION == 1 return ros::Time::now(); #else @@ -573,7 +577,8 @@ ros_Time MVSimNode::myNow() const { #endif } -double MVSimNode::myNowSec() const { +double MVSimNode::myNowSec() const +{ #if PACKAGE_ROS_VERSION == 1 return ros::Time::now().toSec(); #else @@ -583,9 +588,7 @@ double MVSimNode::myNowSec() const { void MVSimNode::sendStaticTF( const std::string& frame_id, const std::string& child_frame_id, - const tf2::Transform& txf, - const ros_Time& stamp -) + const tf2::Transform& txf, const ros_Time& stamp) { Msg_TransformStamped tx; tx.header.frame_id = frame_id; @@ -601,10 +604,11 @@ void MVSimNode::initPubSubs(TPubSubPerVehicle& pubsubs, mvsim::VehicleBase* veh) { // sub: /cmd_vel #if PACKAGE_ROS_VERSION == 1 - pubsubs.sub_cmd_vel = mvsim_node::make_shared(n_.subscribe( - vehVarName("cmd_vel", *veh), 10, - [this, veh](Msg_Twist_CSPtr msg) - { return this->onROSMsgCmdVel(msg, veh); })); + pubsubs.sub_cmd_vel = + mvsim_node::make_shared(n_.subscribe( + vehVarName("cmd_vel", *veh), 10, + [this, veh](Msg_Twist_CSPtr msg) + { return this->onROSMsgCmdVel(msg, veh); })); #else pubsubs.sub_cmd_vel = n_->create_subscription( vehVarName("cmd_vel", *veh), 10, @@ -614,22 +618,28 @@ void MVSimNode::initPubSubs(TPubSubPerVehicle& pubsubs, mvsim::VehicleBase* veh) #if PACKAGE_ROS_VERSION == 1 // pub: /odom - pubsubs.pub_odom = mvsim_node::make_shared(n_.advertise( - vehVarName("odom", *veh), publisher_history_len_)); + pubsubs.pub_odom = + mvsim_node::make_shared(n_.advertise( + vehVarName("odom", *veh), publisher_history_len_)); // pub: /base_pose_ground_truth - pubsubs.pub_ground_truth = mvsim_node::make_shared(n_.advertise( - vehVarName("base_pose_ground_truth", *veh), publisher_history_len_)); + pubsubs.pub_ground_truth = + mvsim_node::make_shared(n_.advertise( + vehVarName("base_pose_ground_truth", *veh), + publisher_history_len_)); // pub: /collision - pubsubs.pub_collision = mvsim_node::make_shared(n_.advertise( - vehVarName("collision", *veh), publisher_history_len_)); + pubsubs.pub_collision = + mvsim_node::make_shared(n_.advertise( + vehVarName("collision", *veh), publisher_history_len_)); // pub: /tf, /tf_static - pubsubs.pub_tf = mvsim_node::make_shared(n_.advertise( - vehVarName("tf", *veh), publisher_history_len_)); - pubsubs.pub_tf_static = mvsim_node::make_shared(n_.advertise( - vehVarName("tf_static", *veh), publisher_history_len_)); + pubsubs.pub_tf = + mvsim_node::make_shared(n_.advertise( + vehVarName("tf", *veh), publisher_history_len_)); + pubsubs.pub_tf_static = + mvsim_node::make_shared(n_.advertise( + vehVarName("tf_static", *veh), publisher_history_len_)); #else // pub: /odom pubsubs.pub_odom = n_->create_publisher( @@ -657,17 +667,16 @@ void MVSimNode::initPubSubs(TPubSubPerVehicle& pubsubs, mvsim::VehicleBase* veh) // pub: /chassis_markers { #if PACKAGE_ROS_VERSION == 1 - pubsubs.pub_chassis_markers = - mvsim_node::make_shared(n_.advertise( + pubsubs.pub_chassis_markers = mvsim_node::make_shared( + n_.advertise( vehVarName("chassis_markers", *veh), 5, true /*latch*/)); #else rclcpp::QoS qosLatched5(rclcpp::KeepLast(5)); qosLatched5.durability(rmw_qos_durability_policy_t:: RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); - pubsubs.pub_chassis_markers = - n_->create_publisher( - vehVarName("chassis_markers", *veh), qosLatched5); + pubsubs.pub_chassis_markers = n_->create_publisher( + vehVarName("chassis_markers", *veh), qosLatched5); #endif const auto& poly = veh->getChassisShape(); @@ -748,16 +757,16 @@ void MVSimNode::initPubSubs(TPubSubPerVehicle& pubsubs, mvsim::VehicleBase* veh) // pub: /chassis_polygon { #if PACKAGE_ROS_VERSION == 1 - pubsubs.pub_chassis_shape = mvsim_node::make_shared(n_.advertise( - vehVarName("chassis_polygon", *veh), 1, true /*latch*/)); + pubsubs.pub_chassis_shape = + mvsim_node::make_shared(n_.advertise( + vehVarName("chassis_polygon", *veh), 1, true /*latch*/)); #else rclcpp::QoS qosLatched1(rclcpp::KeepLast(1)); qosLatched1.durability(rmw_qos_durability_policy_t:: RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); - pubsubs.pub_chassis_shape = - n_->create_publisher( - vehVarName("chassis_polygon", *veh), qosLatched1); + pubsubs.pub_chassis_shape = n_->create_publisher( + vehVarName("chassis_polygon", *veh), qosLatched1); #endif Msg_Polygon poly_msg; @@ -777,21 +786,20 @@ void MVSimNode::initPubSubs(TPubSubPerVehicle& pubsubs, mvsim::VehicleBase* veh) { #if PACKAGE_ROS_VERSION == 1 // pub: /amcl_pose - pubsubs.pub_amcl_pose = - mvsim_node::make_shared(n_.advertise( + pubsubs.pub_amcl_pose = mvsim_node::make_shared( + n_.advertise( vehVarName("amcl_pose", *veh), 1)); // pub: /particlecloud - pubsubs.pub_particlecloud = mvsim_node::make_shared(n_.advertise( - vehVarName("particlecloud", *veh), 1)); + pubsubs.pub_particlecloud = mvsim_node::make_shared( + n_.advertise(vehVarName("particlecloud", *veh), 1)); #else // pub: /amcl_pose pubsubs.pub_amcl_pose = n_->create_publisher( vehVarName("amcl_pose", *veh), 1); // pub: /particlecloud - pubsubs.pub_particlecloud = - n_->create_publisher( - vehVarName("particlecloud", *veh), 1); + pubsubs.pub_particlecloud = n_->create_publisher( + vehVarName("particlecloud", *veh), 1); #endif } @@ -812,13 +820,11 @@ void MVSimNode::initPubSubs(TPubSubPerVehicle& pubsubs, mvsim::VehicleBase* veh) pubsubs.pub_tf_static->publish(tfMsg); } -void MVSimNode::onROSMsgCmdVel( - Msg_Twist_CSPtr cmd, - mvsim::VehicleBase* veh) +void MVSimNode::onROSMsgCmdVel(Msg_Twist_CSPtr cmd, mvsim::VehicleBase* veh) { auto* controller = veh->getControllerInterface(); -// Update cmd_vel timestamp: + // Update cmd_vel timestamp: lastCmdVelTimestamp_[veh] = myNowSec(); const bool ctrlAcceptTwist = controller->setTwistCommand( @@ -1109,11 +1115,12 @@ void MVSimNode::internalOn( if (is_1st_pub) { #if PACKAGE_ROS_VERSION == 1 - pub = mvsim_node::make_shared(n_.advertise( - vehVarName(obs.sensorLabel, veh), publisher_history_len_)); + pub = + mvsim_node::make_shared(n_.advertise( + vehVarName(obs.sensorLabel, veh), publisher_history_len_)); #else - pub = mvsim_node::make_shared>(n_, - vehVarName(obs.sensorLabel, veh), publisher_history_len_); + pub = mvsim_node::make_shared>( + n_, vehVarName(obs.sensorLabel, veh), publisher_history_len_); #endif } lck.unlock(); @@ -1167,8 +1174,8 @@ void MVSimNode::internalOn( pub = mvsim_node::make_shared(n_.advertise( vehVarName(obs.sensorLabel, veh), publisher_history_len_)); #else - pub = mvsim_node::make_shared>(n_, - vehVarName(obs.sensorLabel, veh), publisher_history_len_); + pub = mvsim_node::make_shared>( + n_, vehVarName(obs.sensorLabel, veh), publisher_history_len_); #endif } lck.unlock(); @@ -1223,8 +1230,8 @@ void MVSimNode::internalOn( pub = mvsim_node::make_shared(n_.advertise( vehVarName(obs.sensorLabel, veh), publisher_history_len_)); #else - pub = mvsim_node::make_shared>(n_, - vehVarName(obs.sensorLabel, veh), publisher_history_len_); + pub = mvsim_node::make_shared>( + n_, vehVarName(obs.sensorLabel, veh), publisher_history_len_); #endif } lck.unlock(); @@ -1283,15 +1290,17 @@ void MVSimNode::internalOn( if (is_1st_pub) { #if PACKAGE_ROS_VERSION == 1 - pubImg = mvsim_node::make_shared(n_.advertise( - vehVarName(lbImage, veh), publisher_history_len_)); - pubPts = mvsim_node::make_shared(n_.advertise( - vehVarName(lbPoints, veh), publisher_history_len_)); + pubImg = + mvsim_node::make_shared(n_.advertise( + vehVarName(lbImage, veh), publisher_history_len_)); + pubPts = mvsim_node::make_shared( + n_.advertise( + vehVarName(lbPoints, veh), publisher_history_len_)); #else - pubImg = mvsim_node::make_shared>(n_, - vehVarName(lbImage, veh), publisher_history_len_); - pubPts = mvsim_node::make_shared>(n_, - vehVarName(lbPoints, veh), publisher_history_len_); + pubImg = mvsim_node::make_shared>( + n_, vehVarName(lbImage, veh), publisher_history_len_); + pubPts = mvsim_node::make_shared>( + n_, vehVarName(lbPoints, veh), publisher_history_len_); #endif } lck.unlock(); @@ -1395,11 +1404,12 @@ void MVSimNode::internalOn( if (is_1st_pub) { #if PACKAGE_ROS_VERSION == 1 - pubPts = mvsim_node::make_shared(n_.advertise( - vehVarName(lbPoints, veh), publisher_history_len_)); + pubPts = mvsim_node::make_shared( + n_.advertise( + vehVarName(lbPoints, veh), publisher_history_len_)); #else - pubPts = mvsim_node::make_shared>(n_, - vehVarName(lbPoints, veh), publisher_history_len_); + pubPts = mvsim_node::make_shared>( + n_, vehVarName(lbPoints, veh), publisher_history_len_); #endif } lck.unlock(); diff --git a/mvsim_node_src/mvsim_node_main.cpp b/mvsim_node_src/mvsim_node_main.cpp index 96e681f5..ae12a36e 100644 --- a/mvsim_node_src/mvsim_node_main.cpp +++ b/mvsim_node_src/mvsim_node_main.cpp @@ -30,7 +30,8 @@ int main(int argc, char** argv) try { // Create a "Node" object. - mvsim_node::shared_ptr node = mvsim_node::make_shared(n); + mvsim_node::shared_ptr node = + mvsim_node::make_shared(n); // Declare variables that can be modified by launch file or command // line. @@ -70,9 +71,7 @@ int main(int argc, char** argv) dynamic_reconfigure::Server dr_srv; dr_srv.setCallback( [&node](mvsim::mvsimNodeConfig& config, uint32_t level) - { - return node->configCallback(config, level); - }); + { return node->configCallback(config, level); }); #endif // Tell ROS how fast to run this node->