Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merge latest message #15

Merged
merged 1 commit into from
Dec 17, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef TIER4_AUTO_MSGS_CONVERTER__TIER4_AUTO_MSGS_CONVERTER_HPP_
#define TIER4_AUTO_MSGS_CONVERTER__TIER4_AUTO_MSGS_CONVERTER_HPP_

#include "autoware_auto_perception_msgs/msg/tracked_objects.hpp"
#include "autoware_auto_planning_msgs/msg/path.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
#include "autoware_auto_system_msgs/msg/autoware_state.hpp"
Expand All @@ -29,6 +30,7 @@
#include "autoware_auto_vehicle_msgs/msg/turn_indicators_report.hpp"
#include "tier4_external_api_msgs/msg/gear_shift_stamped.hpp"
#include "tier4_external_api_msgs/msg/turn_signal_stamped.hpp"
#include "tier4_perception_msgs/msg/dynamic_object_array.hpp"
#include "tier4_planning_msgs/msg/path.hpp"
#include "tier4_planning_msgs/msg/trajectory.hpp"
#include "tier4_system_msgs/msg/autoware_state.hpp"
Expand Down Expand Up @@ -276,6 +278,96 @@ inline auto convert(const autoware_auto_vehicle_msgs::msg::SteeringReport & stee
return iv_steering;
}

inline auto convert(const autoware_auto_perception_msgs::msg::ObjectClassification & classification)
{
tier4_perception_msgs::msg::Semantic iv_semantic;
iv_semantic.confidence = classification.probability;
switch (classification.label) {
case autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::UNKNOWN;
break;
case autoware_auto_perception_msgs::msg::ObjectClassification::CAR:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::CAR;
break;
case autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::TRUCK;
break;
case autoware_auto_perception_msgs::msg::ObjectClassification::BUS:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::BUS;
break;
case autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::TRUCK;
break;
case autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::MOTORBIKE;
break;
case autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::BICYCLE;
break;
case autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::PEDESTRIAN;
break;
default:
iv_semantic.type = tier4_perception_msgs::msg::Semantic::UNKNOWN;
break;
}
return iv_semantic;
}

inline auto convert(const autoware_auto_perception_msgs::msg::TrackedObjectKinematics & kinematics)
{
using Kinematics = autoware_auto_perception_msgs::msg::TrackedObjectKinematics;
tier4_perception_msgs::msg::State iv_state;
iv_state.pose_covariance = kinematics.pose_with_covariance;
iv_state.orientation_reliable = (kinematics.orientation_availability == Kinematics::AVAILABLE);
iv_state.twist_covariance = kinematics.twist_with_covariance;
iv_state.twist_reliable = true;
iv_state.acceleration_covariance = kinematics.acceleration_with_covariance;
iv_state.acceleration_reliable = true;
iv_state.predicted_paths = {};
return iv_state;
}

inline auto convert(const autoware_auto_perception_msgs::msg::Shape & shape)
{
tier4_perception_msgs::msg::Shape iv_shape;
iv_shape.dimensions = shape.dimensions;
iv_shape.footprint = shape.footprint;
switch (shape.type) {
case autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX:
iv_shape.type = tier4_perception_msgs::msg::Shape::BOUNDING_BOX;
break;
case autoware_auto_perception_msgs::msg::Shape::CYLINDER:
iv_shape.type = tier4_perception_msgs::msg::Shape::CYLINDER;
break;
case autoware_auto_perception_msgs::msg::Shape::POLYGON:
iv_shape.type = tier4_perception_msgs::msg::Shape::POLYGON;
break;
}
return iv_shape;
}

inline auto convert(const autoware_auto_perception_msgs::msg::TrackedObject & object)
{
tier4_perception_msgs::msg::DynamicObject iv_object;
iv_object.id = object.object_id;
iv_object.semantic = convert(object.classification.front());
iv_object.state = convert(object.kinematics);
iv_object.shape = convert(object.shape);
return iv_object;
}

inline auto convert(const autoware_auto_perception_msgs::msg::TrackedObjects & objects)
{
tier4_perception_msgs::msg::DynamicObjectArray iv_objects;
iv_objects.header = objects.header;
iv_objects.objects.reserve(objects.objects.size());
for (const auto & object : objects.objects) {
iv_objects.objects.push_back(convert(object));
}
return iv_objects;
}

} // namespace tier4_auto_msgs_converter

#endif // TIER4_AUTO_MSGS_CONVERTER__TIER4_AUTO_MSGS_CONVERTER_HPP_
2 changes: 2 additions & 0 deletions tier4_auto_msgs_converter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,11 @@

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_system_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>tier4_perception_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>tier4_system_msgs</depend>
<depend>tier4_vehicle_msgs</depend>
Expand Down
4 changes: 2 additions & 2 deletions tier4_control_msgs/msg/ExternalCommandSelectorMode.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
uint8 NONE=0
uint8 LOCAL=101 # TODO(Takagi, Isamu): temporary value to check data specified by magic number for migration
uint8 REMOTE=102 # TODO(Takagi, Isamu): temporary value to check data specified by magic number for migration
uint8 LOCAL=1
uint8 REMOTE=2
uint8 data
1 change: 0 additions & 1 deletion tier4_external_api_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ rosidl_generate_interfaces(${PROJECT_NAME}
srv/Engage.srv
srv/GetMetadataPackages.srv
srv/GetTextFile.srv
srv/GetVersion.srv
srv/InitializePose.srv
srv/InitializePoseAuto.srv
srv/PauseDriving.srv
Expand Down
3 changes: 0 additions & 3 deletions tier4_external_api_msgs/srv/GetVersion.srv

This file was deleted.