Skip to content

Commit

Permalink
fix: rename package
Browse files Browse the repository at this point in the history
Signed-off-by: Ryohsuke Mitsudome <[email protected]>
  • Loading branch information
mitsudome-r committed Dec 19, 2024
1 parent de0b70c commit 775a0f0
Show file tree
Hide file tree
Showing 16 changed files with 63 additions and 63 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_core_component_interface_specs)
project(autoware_component_interface_specs)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_core_component_interface_specs/README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# autoware_core_component_interface_specs
# autoware_component_interface_specs

This package defines the standardized component interface specifications for Autoware Core, ensuring consistent communication and interaction between various components in the Autoware autonomous driving stack.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__BASE_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__BASE_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__BASE_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__BASE_HPP_

#include <rclcpp/qos.hpp>

#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_map_msgs/msg/map_projector_info.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

namespace autoware::core_component_interface_specs
namespace autoware::component_interface_specs
{

struct InterfaceBase
Expand All @@ -37,6 +37,6 @@ struct InterfaceBase
}
};

} // namespace autoware::core_component_interface_specs
} // namespace autoware::component_interface_specs

#endif // AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__BASE_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__BASE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/base.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_control_msgs/msg/control.hpp>

namespace autoware::core_component_interface_specs::control
namespace autoware::component_interface_specs::control
{

struct ControlCommand : InterfaceBase
Expand All @@ -32,6 +32,6 @@ struct ControlCommand : InterfaceBase
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace autoware::core_component_interface_specs::control
} // namespace autoware::component_interface_specs::control

#endif // AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/base.hpp>
#include <rclcpp/qos.hpp>

#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

namespace autoware::core_component_interface_specs::localization
namespace autoware::component_interface_specs::localization
{

struct KinematicState : InterfaceBase
Expand All @@ -42,6 +42,6 @@ struct Acceleration : InterfaceBase
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware::core_component_interface_specs::localization
} // namespace autoware::component_interface_specs::localization

#endif // AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__MAP_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__MAP_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/base.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_map_msgs/msg/map_projector_info.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

namespace autoware::core_component_interface_specs::map
namespace autoware::component_interface_specs::map
{

struct MapProjectorInfo : InterfaceBase
Expand Down Expand Up @@ -52,6 +52,6 @@ struct VectorMap : InterfaceBase
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace autoware::core_component_interface_specs::map
} // namespace autoware::component_interface_specs::map

#endif // AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__MAP_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/base.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_perception_msgs/msg/predicted_objects.hpp>

namespace autoware::core_component_interface_specs::perception
namespace autoware::component_interface_specs::perception
{

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

} // namespace autoware::core_component_interface_specs::perception
} // namespace autoware::component_interface_specs::perception

#endif // AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/base.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>

namespace autoware::core_component_interface_specs::planning
namespace autoware::component_interface_specs::planning
{

struct LaneletRoute : InterfaceBase
Expand All @@ -42,6 +42,6 @@ struct Trajectory : InterfaceBase
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware::core_component_interface_specs::planning
} // namespace autoware::component_interface_specs::planning

#endif // AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,20 +12,20 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_

#include "base.hpp"

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/base.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_vehicle_msgs/msg/gear_report.hpp>
#include <autoware_vehicle_msgs/msg/hazard_lights_report.hpp>
#include <autoware_vehicle_msgs/msg/steering_report.hpp>
#include <autoware_vehicle_msgs/msg/turn_indicators_report.hpp>

namespace autoware::core_component_interface_specs::vehicle
namespace autoware::component_interface_specs::vehicle
{

struct SteeringStatus : InterfaceBase
Expand Down Expand Up @@ -64,6 +64,6 @@ struct HazardLightStatus : InterfaceBase
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware::core_component_interface_specs::vehicle
} // namespace autoware::component_interface_specs::vehicle

#endif // AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
4 changes: 2 additions & 2 deletions common/autoware_core_component_interface_specs/package.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>autoware_core_component_interface_specs</name>
<name>autoware_component_interface_specs</name>
<version>0.0.0</version>
<description>The autoware_core_component_interface_specs package</description>
<description>The autoware_component_interface_specs package</description>
<maintainer email="[email protected]">Takagi, Isamu</maintainer>
<maintainer email="[email protected]">Yukihiro Saito</maintainer>
<maintainer email="[email protected]">Ryohsuke Mitsudome</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/core_component_interface_specs/control.hpp"
#include "autoware/component_interface_specs/control.hpp"
#include "gtest/gtest.h"

TEST(control, interface)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/core_component_interface_specs/localization.hpp"
#include "autoware/component_interface_specs/localization.hpp"
#include "gtest/gtest.h"

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

{
using autoware::core_component_interface_specs::localization::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 @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/core_component_interface_specs/map.hpp"
#include "autoware/component_interface_specs/map.hpp"
#include "gtest/gtest.h"

TEST(map, interface)
{
{
using autoware::core_component_interface_specs::map::MapProjectorInfo;
using autoware::component_interface_specs::map::MapProjectorInfo;
MapProjectorInfo map_projector;
size_t depth = 1;
EXPECT_EQ(map_projector.depth, depth);
Expand All @@ -27,7 +27,7 @@ TEST(map, interface)
}

{
using autoware::core_component_interface_specs::map::PointCloudMap;
using autoware::component_interface_specs::map::PointCloudMap;
PointCloudMap point_cloud_map;
size_t depth = 1;
EXPECT_EQ(point_cloud_map.depth, depth);
Expand All @@ -36,7 +36,7 @@ TEST(map, interface)
}

{
using autoware::core_component_interface_specs::map::VectorMap;
using autoware::component_interface_specs::map::VectorMap;
VectorMap vector_map;
size_t depth = 1;
EXPECT_EQ(vector_map.depth, depth);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/core_component_interface_specs/perception.hpp"
#include "autoware/component_interface_specs/perception.hpp"
#include "gtest/gtest.h"

TEST(perception, interface)
{
{
using autoware::core_component_interface_specs::perception::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 @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/core_component_interface_specs/planning.hpp"
#include "autoware/component_interface_specs/planning.hpp"
#include "gtest/gtest.h"

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

{
using autoware::core_component_interface_specs::planning::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 @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/core_component_interface_specs/vehicle.hpp"
#include "autoware/component_interface_specs/vehicle.hpp"
#include "gtest/gtest.h"

TEST(vehicle, interface)
{
{
using autoware::core_component_interface_specs::vehicle::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::core_component_interface_specs::vehicle::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::core_component_interface_specs::vehicle::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::core_component_interface_specs::vehicle::HazardLightStatus;
using autoware::component_interface_specs::vehicle::HazardLightStatus;
HazardLightStatus status;
size_t depth = 1;
EXPECT_EQ(status.depth, depth);
Expand Down

0 comments on commit 775a0f0

Please sign in to comment.