Skip to content

Commit

Permalink
drake_ros_*:: -> drake_ros::*:: namespace (#258)
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz authored Mar 14, 2023
1 parent 9672319 commit a6afd7e
Show file tree
Hide file tree
Showing 43 changed files with 238 additions and 176 deletions.
6 changes: 4 additions & 2 deletions drake_ros/core/drake_ros.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,8 @@
#include <rclcpp/executors.hpp>
#include <rclcpp/node.hpp>

namespace drake_ros_core {
namespace drake_ros {
namespace core {
struct DrakeRos::Impl {
rclcpp::Context::SharedPtr context;
rclcpp::Node::UniquePtr node;
Expand Down Expand Up @@ -59,4 +60,5 @@ void init(int argc, const char** argv) {

bool shutdown() { return rclcpp::shutdown(); }

} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/drake_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@
#include <rclcpp/node.hpp>
#include <rclcpp/node_options.hpp>

namespace drake_ros_core {
namespace drake_ros {
namespace core {

/** A Drake ROS interface that wraps a live ROS node.
Expand Down Expand Up @@ -65,4 +66,5 @@ void init(int argc = 0, const char** argv = nullptr);
*/
bool shutdown();

} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/geometry_conversions.cc
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include "drake_ros/core/geometry_conversions.h"

namespace drake_ros_core {
namespace drake_ros {
namespace core {

Eigen::Vector3d RosPointToVector3(const geometry_msgs::msg::Point& point) {
return Eigen::Vector3d(point.x, point.y, point.z);
Expand Down Expand Up @@ -183,4 +184,5 @@ geometry_msgs::msg::Wrench SpatialForceToRosWrench(
return result;
}

} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/geometry_conversions.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,8 @@ expressing it).
#include <geometry_msgs/msg/twist.hpp>
#include <geometry_msgs/msg/wrench.hpp>

namespace drake_ros_core {
namespace drake_ros {
namespace core {

// Vector / Translation.

Expand Down Expand Up @@ -127,4 +128,5 @@ drake::multibody::SpatialForce<double> RosWrenchToSpatialForce(
geometry_msgs::msg::Wrench SpatialForceToRosWrench(
const drake::multibody::SpatialForce<double>& force);

} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/publisher.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,8 @@

#include <rclcpp/version.h>

namespace drake_ros_core {
namespace drake_ros {
namespace core {
namespace internal {
namespace {
// Copied from rosbag2_transport rosbag2_get_publisher_options
Expand Down Expand Up @@ -45,4 +46,5 @@ void Publisher::publish(const rclcpp::SerializedMessage& serialized_msg) {
}
}
} // namespace internal
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@
#include <rclcpp/serialized_message.hpp>
#include <rosidl_runtime_c/message_type_support_struct.h>

namespace drake_ros_core {
namespace drake_ros {
namespace core {
namespace internal {
// A type-erased version of rclcpp:::Publisher<Message>.
// This class conforms to the ROS 2 C++ style for consistency.
Expand All @@ -23,4 +24,5 @@ class Publisher final : public rclcpp::PublisherBase {
void publish(const rclcpp::SerializedMessage& serialized_msg);
};
} // namespace internal
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/ros_interface_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,8 @@
#include <memory>
#include <utility>

namespace drake_ros_core {
namespace drake_ros {
namespace core {
struct RosInterfaceSystem::Impl {
// Interface to ROS (through a node).
std::unique_ptr<DrakeRos> ros;
Expand Down Expand Up @@ -32,4 +33,5 @@ void RosInterfaceSystem::DoCalcNextUpdateTime(
// order of node spinning and message taking affects it?
*time = std::numeric_limits<double>::infinity();
}
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/ros_interface_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@

#include "drake_ros/core/drake_ros.h"

namespace drake_ros_core {
namespace drake_ros {
namespace core {
/** A system that manages a Drake ROS interface. */
class RosInterfaceSystem : public drake::systems::LeafSystem<double> {
public:
Expand All @@ -27,4 +28,5 @@ class RosInterfaceSystem : public drake::systems::LeafSystem<double> {
struct Impl;
std::unique_ptr<Impl> impl_;
};
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/ros_publisher_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@

#include "drake_ros/core/serializer_interface.h"

namespace drake_ros_core {
namespace drake_ros {
namespace core {
struct RosPublisherSystem::Impl {
// Interface for message (de)serialization.
std::unique_ptr<SerializerInterface> serializer;
Expand Down Expand Up @@ -89,4 +90,5 @@ drake::systems::EventStatus RosPublisherSystem::PublishInput(
impl_->pub->publish(impl_->serializer->Serialize(input));
return drake::systems::EventStatus::Succeeded();
}
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/ros_publisher_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@
#include "drake_ros/core/serializer.h"
#include "drake_ros/core/serializer_interface.h"

namespace drake_ros_core {
namespace drake_ros {
namespace core {
/** A system that can publish ROS messages.
It accepts ROS messages on its sole input port and publishes them
to a ROS topic.
Expand Down Expand Up @@ -83,4 +84,5 @@ class RosPublisherSystem : public drake::systems::LeafSystem<double> {
struct Impl;
std::unique_ptr<Impl> impl_;
};
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/ros_subscriber_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@
#include "subscription.h" // NOLINT(build/include)
#include <drake/systems/framework/abstract_values.h>

namespace drake_ros_core {
namespace drake_ros {
namespace core {
namespace {
// A synchronized queue of `MessageT` messages.
template <typename MessageT>
Expand Down Expand Up @@ -110,4 +111,5 @@ void RosSubscriberSystem::DoCalcNextUpdateTime(
uu_events.AddEvent(drake::systems::UnrestrictedUpdateEvent<double>(
drake::systems::TriggerType::kTimed, callback));
}
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/ros_subscriber_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,8 @@
#include "drake_ros/core/serializer.h"
#include "drake_ros/core/serializer_interface.h"

namespace drake_ros_core {
namespace drake_ros {
namespace core {
/** A system that can subscribe to ROS messages.
It subscribes to a ROS topic and makes ROS messages available on
its sole output port.
Expand Down Expand Up @@ -55,4 +56,5 @@ class RosSubscriberSystem : public drake::systems::LeafSystem<double> {
struct Impl;
std::unique_ptr<Impl> impl_;
};
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/serializer.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@

#include "drake_ros/core/serializer_interface.h"

namespace drake_ros_core {
namespace drake_ros {
namespace core {
/** A (de)serialization interface implementation that is
bound to C++ ROS messages of `MessageT` type. */
template <typename MessageT>
Expand Down Expand Up @@ -40,4 +41,5 @@ class Serializer : public SerializerInterface {
private:
rclcpp::Serialization<MessageT> protocol_;
};
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/serializer_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@
#include <rclcpp/serialized_message.hpp>
#include <rosidl_typesupport_cpp/message_type_support.hpp>

namespace drake_ros_core {
namespace drake_ros {
namespace core {
/** An interface for (de)serialization of a ROS message.
This interface deals with ROS messages of a fixed message
Expand Down Expand Up @@ -42,4 +43,5 @@ class SerializerInterface {
/** Returns a reference to the ROS message typesupport. */
virtual const rosidl_message_type_support_t* GetTypeSupport() const = 0;
};
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/subscription.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@

#include <rclcpp/version.h>

namespace drake_ros_core {
namespace drake_ros {
namespace core {
namespace internal {
namespace {
// Copied from rosbag2_transport rosbag2_get_subscription_options
Expand Down Expand Up @@ -80,4 +81,5 @@ void Subscription::return_serialized_message(
message.reset();
}
} // namespace internal
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 4 additions & 2 deletions drake_ros/core/subscription.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@
#include <rmw/serialized_message.h>
#include <rosidl_runtime_c/message_type_support_struct.h>

namespace drake_ros_core {
namespace drake_ros {
namespace core {
namespace internal {
// A type-erased version of rclcpp:::Subscription<Message>.
// This class conforms to the ROS 2 C++ style for consistency.
Expand Down Expand Up @@ -60,4 +61,5 @@ class Subscription final : public rclcpp::SubscriptionBase {
std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback_;
};
} // namespace internal
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
6 changes: 3 additions & 3 deletions drake_ros/core/test/test_drake_ros.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,12 @@

#include "drake_ros/core/drake_ros.h"

using drake_ros_core::DrakeRos;
using drake_ros::core::DrakeRos;

TEST(DrakeRos, default_construct) {
drake_ros_core::init();
drake_ros::core::init();
EXPECT_NO_THROW(std::make_unique<DrakeRos>("default_node"));
EXPECT_TRUE(drake_ros_core::shutdown());
EXPECT_TRUE(drake_ros::core::shutdown());
}

TEST(DrakeRos, local_context) {
Expand Down
6 changes: 4 additions & 2 deletions drake_ros/core/test/test_geometry_conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@

#include "drake_ros/core/geometry_conversions.h"

namespace drake_ros_core {
namespace drake_ros {
namespace core {
namespace {

// N.B. For the purpose of testing type conversions, we should use explicit
Expand Down Expand Up @@ -312,4 +313,5 @@ TEST(GeometryConversions, Force) {
}

} // namespace
} // namespace drake_ros_core
} // namespace core
} // namespace drake_ros
12 changes: 6 additions & 6 deletions drake_ros/core/test/test_pub_sub.cc
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,13 @@
#include "drake_ros/core/ros_publisher_system.h"
#include "drake_ros/core/ros_subscriber_system.h"

using drake_ros_core::DrakeRos;
using drake_ros_core::RosInterfaceSystem;
using drake_ros_core::RosPublisherSystem;
using drake_ros_core::RosSubscriberSystem;
using drake_ros::core::DrakeRos;
using drake_ros::core::RosInterfaceSystem;
using drake_ros::core::RosPublisherSystem;
using drake_ros::core::RosSubscriberSystem;

TEST(Integration, sub_to_pub) {
drake_ros_core::init(0, nullptr);
drake_ros::core::init(0, nullptr);

drake::systems::DiagramBuilder<double> builder;

Expand Down Expand Up @@ -90,7 +90,7 @@ TEST(Integration, sub_to_pub) {
EXPECT_EQ(rx_msgs_direct_sub_out.back()->uint64_value, i);
}

drake_ros_core::shutdown();
drake_ros::core::shutdown();
}

// Only available in Bazel.
Expand Down
Loading

0 comments on commit a6afd7e

Please sign in to comment.