Skip to content

Commit 4d72d33

Browse files
Renamed ros_controllers namespace to individual controller namespace (ros-navigation#23)
1 parent 40b858b commit 4d72d33

File tree

8 files changed

+23
-23
lines changed

8 files changed

+23
-23
lines changed

joint_state_controller/include/joint_state_controller/joint_state_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727

2828
#include "sensor_msgs/msg/joint_state.hpp"
2929

30-
namespace ros_controllers
30+
namespace joint_state_controller
3131
{
3232

3333
class JointStateController : public controller_interface::ControllerInterface
@@ -51,6 +51,6 @@ class JointStateController : public controller_interface::ControllerInterface
5151
sensor_msgs::msg::JointState joint_state_msg_;
5252
};
5353

54-
} // namespace ros_controllers
54+
} // namespace joint_state_controller
5555

5656
#endif // JOINT_STATE_CONTROLLER__JOINT_STATE_CONTROLLER_HPP_

joint_state_controller/src/joint_state_controller.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121

2222
#include "rcutils/logging_macros.h"
2323

24-
namespace ros_controllers
24+
namespace joint_state_controller
2525
{
2626

2727
JointStateController::JointStateController()
@@ -83,9 +83,9 @@ JointStateController::update()
8383
return hardware_interface::HW_RET_OK;
8484
}
8585

86-
} // namespace ros_controllers
86+
} // namespace joint_state_controller
8787

8888
#include "pluginlib/class_list_macros.hpp"
8989

9090
PLUGINLIB_EXPORT_CLASS(
91-
ros_controllers::JointStateController, controller_interface::ControllerInterface)
91+
joint_state_controller::JointStateController, controller_interface::ControllerInterface)

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@
3535
#include "trajectory_msgs/msg/joint_trajectory.hpp"
3636
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
3737

38-
namespace ros_controllers
38+
namespace joint_trajectory_controller
3939
{
4040

4141
class JointTrajectoryController : public controller_interface::ControllerInterface
@@ -109,6 +109,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
109109
void halt();
110110
};
111111

112-
} // namespace ros_controllers
112+
} // namespace joint_trajectory_controller
113113

114114
#endif // JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_

joint_trajectory_controller/include/joint_trajectory_controller/trajectory.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424

2525
#include "trajectory_msgs/msg/joint_trajectory.hpp"
2626

27-
namespace ros_controllers
27+
namespace joint_trajectory_controller
2828
{
2929

3030
using TrajectoryPointIter =
@@ -82,6 +82,6 @@ class Trajectory
8282
rclcpp::Time trajectory_start_time_;
8383
};
8484

85-
} // namespace ros_controllers
85+
} // namespace joint_trajectory_controller
8686

8787
#endif // JOINT_TRAJECTORY_CONTROLLER__TRAJECTORY_HPP_

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434
#include "trajectory_msgs/msg/joint_trajectory.hpp"
3535
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
3636

37-
namespace ros_controllers
37+
namespace joint_trajectory_controller
3838
{
3939

4040
using namespace std::chrono_literals;
@@ -325,9 +325,9 @@ JointTrajectoryController::halt()
325325
set_op_mode(hardware_interface::OperationMode::ACTIVE);
326326
}
327327

328-
} // namespace ros_controllers
328+
} // namespace joint_trajectory_controller
329329

330330
#include "pluginlib/class_list_macros.hpp"
331331

332332
PLUGINLIB_EXPORT_CLASS(
333-
ros_controllers::JointTrajectoryController, controller_interface::ControllerInterface)
333+
joint_trajectory_controller::JointTrajectoryController, controller_interface::ControllerInterface)

joint_trajectory_controller/src/trajectory.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121

2222
#include "rclcpp/clock.hpp"
2323

24-
namespace ros_controllers
24+
namespace joint_trajectory_controller
2525
{
2626

2727
// TODO(karsten1987): Fix to rclcpp time when API stable.
@@ -99,4 +99,4 @@ Trajectory::is_empty() const
9999
return !trajectory_msg_;
100100
}
101101

102-
} // namespace ros_controllers
102+
} // namespace joint_trajectory_controller

joint_trajectory_controller/test/test_trajectory.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ TEST_F(TestTrajectory, initialize_trajectory) {
3939
empty_msg->header.stamp.sec = 2;
4040
empty_msg->header.stamp.nanosec = 2;
4141
rclcpp::Time empty_time = empty_msg->header.stamp;
42-
auto traj = ros_controllers::Trajectory(empty_msg);
42+
auto traj = joint_trajectory_controller::Trajectory(empty_msg);
4343
EXPECT_EQ(traj.end(), traj.sample(rclcpp::Clock().now()));
4444
EXPECT_EQ(empty_time, traj.time_from_start());
4545
}
@@ -48,7 +48,7 @@ TEST_F(TestTrajectory, initialize_trajectory) {
4848
empty_msg->header.stamp.sec = 0;
4949
empty_msg->header.stamp.nanosec = 0;
5050
auto now = rclcpp::Clock().now();
51-
auto traj = ros_controllers::Trajectory(empty_msg);
51+
auto traj = joint_trajectory_controller::Trajectory(empty_msg);
5252
auto traj_starttime = traj.time_from_start();
5353
EXPECT_EQ(traj.end(), traj.sample(rclcpp::Clock().now()));
5454
auto allowed_delta = 10000ll;
@@ -86,7 +86,7 @@ TEST_F(TestTrajectory, sample_trajectory) {
8686
full_msg->points.push_back(p2);
8787
full_msg->points.push_back(p3);
8888

89-
auto traj = ros_controllers::Trajectory(full_msg);
89+
auto traj = joint_trajectory_controller::Trajectory(full_msg);
9090

9191
auto sample_p1 = traj.sample(rclcpp::Clock().now());
9292
ASSERT_NE(traj.end(), sample_p1);
@@ -155,7 +155,7 @@ TEST_F(TestTrajectory, future_sample_trajectory) {
155155
full_msg->points.push_back(p2);
156156
full_msg->points.push_back(p3);
157157

158-
auto traj = ros_controllers::Trajectory(full_msg);
158+
auto traj = joint_trajectory_controller::Trajectory(full_msg);
159159

160160
// sample for future point
161161
auto sample_p0 = traj.sample(rclcpp::Clock().now());

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ class TestTrajectoryController : public ::testing::Test
133133

134134
TEST_F(TestTrajectoryController, wrong_initialization) {
135135
auto uninitialized_robot = std::make_shared<test_robot_hardware::TestRobotHardware>();
136-
auto traj_controller = std::make_shared<ros_controllers::JointTrajectoryController>(
136+
auto traj_controller = std::make_shared<joint_trajectory_controller::JointTrajectoryController>(
137137
joint_names, op_mode);
138138
auto ret = traj_controller->init(uninitialized_robot, controller_name);
139139
if (ret != controller_interface::CONTROLLER_INTERFACE_RET_SUCCESS) {
@@ -147,7 +147,7 @@ TEST_F(TestTrajectoryController, wrong_initialization) {
147147
TEST_F(TestTrajectoryController, correct_initialization) {
148148
auto initialized_robot = std::make_shared<test_robot_hardware::TestRobotHardware>();
149149
initialized_robot->init();
150-
auto traj_controller = std::make_shared<ros_controllers::JointTrajectoryController>(
150+
auto traj_controller = std::make_shared<joint_trajectory_controller::JointTrajectoryController>(
151151
joint_names, op_mode);
152152
auto ret = traj_controller->init(initialized_robot, controller_name);
153153
if (ret != controller_interface::CONTROLLER_INTERFACE_RET_SUCCESS) {
@@ -162,7 +162,7 @@ TEST_F(TestTrajectoryController, correct_initialization) {
162162
}
163163

164164
TEST_F(TestTrajectoryController, configuration) {
165-
auto traj_controller = std::make_shared<ros_controllers::JointTrajectoryController>(
165+
auto traj_controller = std::make_shared<joint_trajectory_controller::JointTrajectoryController>(
166166
joint_names, op_mode);
167167
auto ret = traj_controller->init(test_robot, controller_name);
168168
if (ret != controller_interface::CONTROLLER_INTERFACE_RET_SUCCESS) {
@@ -309,7 +309,7 @@ TEST_F(TestTrajectoryController, configuration) {
309309
// }
310310

311311
TEST_F(TestTrajectoryController, cleanup) {
312-
auto traj_controller = std::make_shared<ros_controllers::JointTrajectoryController>(
312+
auto traj_controller = std::make_shared<joint_trajectory_controller::JointTrajectoryController>(
313313
joint_names, op_mode);
314314
auto ret = traj_controller->init(test_robot, controller_name);
315315
if (ret != controller_interface::CONTROLLER_INTERFACE_RET_SUCCESS) {
@@ -361,7 +361,7 @@ TEST_F(TestTrajectoryController, cleanup) {
361361
}
362362

363363
TEST_F(TestTrajectoryController, correct_initialization_using_parameters) {
364-
auto traj_controller = std::make_shared<ros_controllers::JointTrajectoryController>();
364+
auto traj_controller = std::make_shared<joint_trajectory_controller::JointTrajectoryController>();
365365
auto ret = traj_controller->init(test_robot, controller_name);
366366
if (ret != controller_interface::CONTROLLER_INTERFACE_RET_SUCCESS) {
367367
FAIL();

0 commit comments

Comments
 (0)