Skip to content

Commit

Permalink
shorten namespaces
Browse files Browse the repository at this point in the history
Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Oct 21, 2024
1 parent 8b357dd commit 11dbeef
Show file tree
Hide file tree
Showing 42 changed files with 130 additions and 130 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include <tier4_control_msgs/srv/set_pause.hpp>
#include <tier4_control_msgs/srv/set_stop.hpp>

namespace autoware::component_interface_specs::control_interface
namespace autoware::component_interface_specs::control
{

struct SetPause
Expand Down Expand Up @@ -65,6 +65,6 @@ struct IsStopped
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace autoware::component_interface_specs::control_interface
} // namespace autoware::component_interface_specs::control

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_localization_msgs/srv/initialize_localization.hpp>

namespace autoware::component_interface_specs::localization_interface
namespace autoware::component_interface_specs::localization
{

struct Initialize
Expand Down Expand Up @@ -58,6 +58,6 @@ struct Acceleration
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware::component_interface_specs::localization_interface
} // namespace autoware::component_interface_specs::localization

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <tier4_map_msgs/msg/map_projector_info.hpp>

namespace autoware::component_interface_specs::map_interface
namespace autoware::component_interface_specs::map
{

struct MapProjectorInfo
Expand All @@ -31,6 +31,6 @@ struct MapProjectorInfo
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace autoware::component_interface_specs::map_interface
} // namespace autoware::component_interface_specs::map

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <autoware_perception_msgs/msg/predicted_objects.hpp>

namespace autoware::component_interface_specs::perception_interface
namespace autoware::component_interface_specs::perception
{

struct ObjectRecognition
Expand All @@ -31,6 +31,6 @@ struct ObjectRecognition
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware::component_interface_specs::perception_interface
} // namespace autoware::component_interface_specs::perception

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <tier4_planning_msgs/srv/set_lanelet_route.hpp>
#include <tier4_planning_msgs/srv/set_waypoint_route.hpp>

namespace autoware::component_interface_specs::planning_interface
namespace autoware::component_interface_specs::planning
{

struct SetLaneletRoute
Expand Down Expand Up @@ -73,6 +73,6 @@ struct Trajectory
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware::component_interface_specs::planning_interface
} // namespace autoware::component_interface_specs::planning

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <tier4_system_msgs/srv/change_autoware_control.hpp>
#include <tier4_system_msgs/srv/change_operation_mode.hpp>

namespace autoware::component_interface_specs::system_interface
namespace autoware::component_interface_specs::system
{

struct MrmState
Expand Down Expand Up @@ -55,6 +55,6 @@ struct OperationModeState
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace autoware::component_interface_specs::system_interface
} // namespace autoware::component_interface_specs::system

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <autoware_vehicle_msgs/msg/turn_indicators_report.hpp>
#include <tier4_vehicle_msgs/msg/battery_status.hpp>

namespace autoware::component_interface_specs::vehicle_interface
namespace autoware::component_interface_specs::vehicle
{

struct SteeringStatus
Expand Down Expand Up @@ -95,6 +95,6 @@ struct DoorStatus
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware::component_interface_specs::vehicle_interface
} // namespace autoware::component_interface_specs::vehicle

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
TEST(control, interface)
{
{
using autoware::component_interface_specs::control_interface::IsPaused;
using autoware::component_interface_specs::control::IsPaused;
IsPaused is_paused;
size_t depth = 1;
EXPECT_EQ(is_paused.depth, depth);
Expand All @@ -27,7 +27,7 @@ TEST(control, interface)
}

{
using autoware::component_interface_specs::control_interface::IsStartRequested;
using autoware::component_interface_specs::control::IsStartRequested;
IsStartRequested is_start_requested;
size_t depth = 1;
EXPECT_EQ(is_start_requested.depth, depth);
Expand All @@ -36,7 +36,7 @@ TEST(control, interface)
}

{
using autoware::component_interface_specs::control_interface::IsStopped;
using autoware::component_interface_specs::control::IsStopped;
IsStopped is_stopped;
size_t depth = 1;
EXPECT_EQ(is_stopped.depth, depth);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
TEST(localization, interface)
{
{
using autoware::component_interface_specs::localization_interface::InitializationState;
using autoware::component_interface_specs::localization::InitializationState;
InitializationState initialization_state;
size_t depth = 1;
EXPECT_EQ(initialization_state.depth, depth);
Expand All @@ -27,7 +27,7 @@ TEST(localization, interface)
}

{
using autoware::component_interface_specs::localization_interface::KinematicState;
using autoware::component_interface_specs::localization::KinematicState;
KinematicState kinematic_state;
size_t depth = 1;
EXPECT_EQ(kinematic_state.depth, depth);
Expand All @@ -36,7 +36,7 @@ TEST(localization, interface)
}

{
using autoware::component_interface_specs::localization_interface::Acceleration;
using autoware::component_interface_specs::localization::Acceleration;
Acceleration acceleration;
size_t depth = 1;
EXPECT_EQ(acceleration.depth, depth);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
TEST(map, interface)
{
{
using autoware::component_interface_specs::map_interface::MapProjectorInfo;
using autoware::component_interface_specs::map::MapProjectorInfo;
MapProjectorInfo map_projector;
size_t depth = 1;
EXPECT_EQ(map_projector.depth, depth);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
TEST(perception, interface)
{
{
using autoware::component_interface_specs::perception_interface::ObjectRecognition;
using autoware::component_interface_specs::perception::ObjectRecognition;
ObjectRecognition object_recognition;
size_t depth = 1;
EXPECT_EQ(object_recognition.depth, depth);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
TEST(planning, interface)
{
{
using autoware::component_interface_specs::planning_interface::RouteState;
using autoware::component_interface_specs::planning::RouteState;
RouteState state;
size_t depth = 1;
EXPECT_EQ(state.depth, depth);
Expand All @@ -27,7 +27,7 @@ TEST(planning, interface)
}

{
using autoware::component_interface_specs::planning_interface::LaneletRoute;
using autoware::component_interface_specs::planning::LaneletRoute;
LaneletRoute route;
size_t depth = 1;
EXPECT_EQ(route.depth, depth);
Expand All @@ -36,7 +36,7 @@ TEST(planning, interface)
}

{
using autoware::component_interface_specs::planning_interface::Trajectory;
using autoware::component_interface_specs::planning::Trajectory;
Trajectory trajectory;
size_t depth = 1;
EXPECT_EQ(trajectory.depth, depth);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
TEST(system, interface)
{
{
using autoware::component_interface_specs::system_interface::MrmState;
using autoware::component_interface_specs::system::MrmState;
MrmState state;
size_t depth = 1;
EXPECT_EQ(state.depth, depth);
Expand All @@ -27,7 +27,7 @@ TEST(system, interface)
}

{
using autoware::component_interface_specs::system_interface::OperationModeState;
using autoware::component_interface_specs::system::OperationModeState;
OperationModeState state;
size_t depth = 1;
EXPECT_EQ(state.depth, depth);
Expand Down
10 changes: 5 additions & 5 deletions common/autoware_component_interface_specs/test/test_vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
TEST(vehicle, interface)
{
{
using autoware::component_interface_specs::vehicle_interface::SteeringStatus;
using autoware::component_interface_specs::vehicle::SteeringStatus;
SteeringStatus status;
size_t depth = 1;
EXPECT_EQ(status.depth, depth);
Expand All @@ -27,7 +27,7 @@ TEST(vehicle, interface)
}

{
using autoware::component_interface_specs::vehicle_interface::GearStatus;
using autoware::component_interface_specs::vehicle::GearStatus;
GearStatus status;
size_t depth = 1;
EXPECT_EQ(status.depth, depth);
Expand All @@ -36,7 +36,7 @@ TEST(vehicle, interface)
}

{
using autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus;
using autoware::component_interface_specs::vehicle::TurnIndicatorStatus;
TurnIndicatorStatus status;
size_t depth = 1;
EXPECT_EQ(status.depth, depth);
Expand All @@ -45,7 +45,7 @@ TEST(vehicle, interface)
}

{
using autoware::component_interface_specs::vehicle_interface::HazardLightStatus;
using autoware::component_interface_specs::vehicle::HazardLightStatus;
HazardLightStatus status;
size_t depth = 1;
EXPECT_EQ(status.depth, depth);
Expand All @@ -54,7 +54,7 @@ TEST(vehicle, interface)
}

{
using autoware::component_interface_specs::vehicle_interface::EnergyStatus;
using autoware::component_interface_specs::vehicle::EnergyStatus;
EnergyStatus status;
size_t depth = 1;
EXPECT_EQ(status.depth, depth);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,11 @@ class OperationModeTransitionManager : public rclcpp::Node

private:
using ChangeAutowareControlAPI =
autoware::component_interface_specs::system_interface::ChangeAutowareControl;
autoware::component_interface_specs::system::ChangeAutowareControl;
using ChangeOperationModeAPI =
autoware::component_interface_specs::system_interface::ChangeOperationMode;
autoware::component_interface_specs::system::ChangeOperationMode;
using OperationModeStateAPI =
autoware::component_interface_specs::system_interface::OperationModeState;
autoware::component_interface_specs::system::OperationModeState;
component_interface_utils::Service<ChangeAutowareControlAPI>::SharedPtr srv_autoware_control_;
component_interface_utils::Service<ChangeOperationModeAPI>::SharedPtr srv_operation_mode_;
component_interface_utils::Publisher<OperationModeStateAPI>::SharedPtr pub_operation_mode_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,9 @@ class AdapiPauseInterface
private:
static constexpr double eps = 1e-3;
using Control = autoware_control_msgs::msg::Control;
using SetPause = autoware::component_interface_specs::control_interface::SetPause;
using IsPaused = autoware::component_interface_specs::control_interface::IsPaused;
using IsStartRequested = autoware::component_interface_specs::control_interface::IsStartRequested;
using SetPause = autoware::component_interface_specs::control::SetPause;
using IsPaused = autoware::component_interface_specs::control::IsPaused;
using IsStartRequested = autoware::component_interface_specs::control::IsStartRequested;

public:
explicit AdapiPauseInterface(rclcpp::Node * node);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@ namespace autoware::vehicle_cmd_gate
class ModerateStopInterface
{
private:
using SetStop = autoware::component_interface_specs::control_interface::SetStop;
using IsStopped = autoware::component_interface_specs::control_interface::IsStopped;
using IsStartRequested = autoware::component_interface_specs::control_interface::IsStartRequested;
using SetStop = autoware::component_interface_specs::control::SetStop;
using IsStopped = autoware::component_interface_specs::control::IsStopped;
using IsStartRequested = autoware::component_interface_specs::control::IsStartRequested;

public:
explicit ModerateStopInterface(rclcpp::Node * node);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,11 +97,11 @@ class PredictedPathCheckerNode : public rclcpp::Node
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
rclcpp::Subscription<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr sub_accel_;
component_interface_utils::Subscription<
autoware::component_interface_specs::control_interface::IsStopped>::SharedPtr sub_stop_state_;
autoware::component_interface_specs::control::IsStopped>::SharedPtr sub_stop_state_;

// Client
component_interface_utils::Client<
autoware::component_interface_specs::control_interface::SetStop>::SharedPtr cli_set_stop_;
autoware::component_interface_specs::control::SetStop>::SharedPtr cli_set_stop_;

// Data Buffer
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_;
Expand All @@ -110,7 +110,7 @@ class PredictedPathCheckerNode : public rclcpp::Node
PredictedObjects::ConstSharedPtr object_ptr_{nullptr};
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory_;
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory_;
autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr
autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr
is_stopped_ptr_{nullptr};

// Core
Expand All @@ -130,7 +130,7 @@ class PredictedPathCheckerNode : public rclcpp::Node
void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg);
void onAccel(const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg);
void onIsStopped(
const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr
const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr
msg);

// Timer
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ void PredictedPathCheckerNode::onAccel(
}

void PredictedPathCheckerNode::onIsStopped(
const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr
const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr
msg)
{
is_stopped_ptr_ = msg;
Expand Down Expand Up @@ -417,7 +417,7 @@ void PredictedPathCheckerNode::sendRequest(bool make_stop_vehicle)
{
if (!is_calling_set_stop_ && cli_set_stop_->service_is_ready()) {
const auto req = std::make_shared<
autoware::component_interface_specs::control_interface::SetStop::Service::Request>();
autoware::component_interface_specs::control::SetStop::Service::Request>();
req->stop = make_stop_vehicle;
req->request_source = "predicted_path_checker";
is_calling_set_stop_ = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class GeoPoseProjector : public rclcpp::Node
private:
using GeoPoseWithCovariance = geographic_msgs::msg::GeoPoseWithCovarianceStamped;
using PoseWithCovariance = geometry_msgs::msg::PoseWithCovarianceStamped;
using MapProjectorInfo = autoware::component_interface_specs::map_interface::MapProjectorInfo;
using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo;

public:
explicit GeoPoseProjector(const rclcpp::NodeOptions & options);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
namespace autoware::pose_initializer
{
using ServiceException = component_interface_utils::ServiceException;
using Initialize = autoware::component_interface_specs::localization_interface::Initialize;
using Initialize = autoware::component_interface_specs::localization::Initialize;

EkfLocalizationTriggerModule::EkfLocalizationTriggerModule(rclcpp::Node * node) : node_(node)
{
Expand Down
2 changes: 1 addition & 1 deletion localization/autoware_pose_initializer/src/gnss_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ void GnssModule::on_pose(PoseWithCovarianceStamped::ConstSharedPtr msg)

geometry_msgs::msg::PoseWithCovarianceStamped GnssModule::get_pose()
{
using Initialize = autoware::component_interface_specs::localization_interface::Initialize;
using Initialize = autoware::component_interface_specs::localization::Initialize;

if (!pose_) {
throw component_interface_utils::ServiceException(
Expand Down
Loading

0 comments on commit 11dbeef

Please sign in to comment.