Skip to content

Commit

Permalink
Merge pull request #10 from mitsudome-r/revert-ros1
Browse files Browse the repository at this point in the history
Revert ros1
  • Loading branch information
mitsudome-r authored Oct 8, 2020
2 parents cd5c7e4 + 22fe078 commit 4d45188
Show file tree
Hide file tree
Showing 1,359 changed files with 137,246 additions and 0 deletions.
39 changes: 39 additions & 0 deletions awapi/autoware_api_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
cmake_minimum_required(VERSION 3.0.2)
project(autoware_api_msgs)

add_compile_options(-std=c++14)

find_package(catkin REQUIRED COMPONENTS
std_msgs
geometry_msgs
diagnostic_msgs
autoware_planning_msgs
)

add_message_files(
DIRECTORY msg
FILES
Latlon.msg
Euler.msg
AwapiVehicleStatus.msg
AwapiAutowareStatus.msg
LaneChangeStatus.msg
ObstacleAvoidanceStatus.msg
)

generate_messages(
DEPENDENCIES
std_msgs
geometry_msgs
diagnostic_msgs
autoware_planning_msgs
)

catkin_package(
CATKIN_DEPENDS
message_runtime
std_msgs
geometry_msgs
diagnostic_msgs
autoware_planning_msgs
)
Empty file.
9 changes: 9 additions & 0 deletions awapi/autoware_api_msgs/msg/AwapiAutowareStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
Header header
string autoware_state
int32 control_mode
int32 gate_mode
bool emergency_stopped
autoware_planning_msgs/StopReasonArray stop_reason
diagnostic_msgs/DiagnosticStatus[] diagnostics
bool autonomous_overriden
bool arrived_goal
16 changes: 16 additions & 0 deletions awapi/autoware_api_msgs/msg/AwapiVehicleStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
std_msgs/Header header
geometry_msgs/Pose pose
autoware_api_msgs/Euler eulerangle
autoware_api_msgs/Latlon latlon
float64 velocity
float64 acceleration
float64 steering
float64 steering_velocity
float64 angular_velocity
int32 gear
float32 energy_level
int32 turn_signal
float64 target_velocity
float64 target_acceleration
float64 target_steering
float64 target_steering_velocity
3 changes: 3 additions & 0 deletions awapi/autoware_api_msgs/msg/Euler.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
float64 roll
float64 pitch
float64 yaw
4 changes: 4 additions & 0 deletions awapi/autoware_api_msgs/msg/LaneChangeStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
Header header
bool force_lane_change_available
bool lane_change_ready
autoware_planning_msgs/Path candidate_path
3 changes: 3 additions & 0 deletions awapi/autoware_api_msgs/msg/Latlon.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
float64 lat
float64 lon
float64 alt
3 changes: 3 additions & 0 deletions awapi/autoware_api_msgs/msg/ObstacleAvoidanceStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
Header header
bool obstacle_avoidance_ready
autoware_planning_msgs/Trajectory candidate_path
20 changes: 20 additions & 0 deletions awapi/autoware_api_msgs/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<package format="2">
<name>autoware_api_msgs</name>
<version>0.1.0</version>
<description>The autoware_api_msgs package</description>
<maintainer email="tomoya.kimura@tier4.jp">Tomoya Kimura</maintainer>
<author email="tomoya.kimura@tier4.jp">Tomoya Kimura</author>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>

<depend>message_generation</depend>
<depend>message_runtime</depend>
<depend>roscpp</depend>
<depend>std_msgs</depend>
<depend>geometry_msgs</depend>
<depend>diagnostic_msgs</depend>
<depend>autoware_planning_msgs</depend>
<export></export>
</package>
70 changes: 70 additions & 0 deletions awapi/awapi_awiv_adapter/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
cmake_minimum_required(VERSION 3.0.2)
project(awapi_awiv_adapter)

add_compile_options(-std=c++14)

find_package(catkin REQUIRED COMPONENTS
message_generation
message_runtime
roscpp
autoware_api_msgs
autoware_system_msgs
autoware_planning_msgs
autoware_control_msgs
autoware_vehicle_msgs
diagnostic_msgs
geometry_msgs
pacmod_msgs
std_msgs
sensor_msgs
tf2
tf2_geometry_msgs
)

catkin_package(
INCLUDE_DIRS include
)

include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_executable(awapi_awiv_adapter
src/awapi_awiv_adapter_node.cpp
src/awapi_awiv_adapter_core.cpp
src/awapi_vehicle_state_publisher.cpp
src/awapi_autoware_state_publisher.cpp
src/awapi_stop_reason_aggregator.cpp
src/awapi_lane_change_state_publisher.cpp
src/awapi_obstacle_avoidance_state_publisher.cpp
src/awapi_autoware_util.cpp
)

target_link_libraries(awapi_awiv_adapter
${catkin_LIBRARIES}
)

add_dependencies(awapi_awiv_adapter
${catkin_EXPORTED_TARGETS}
)

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)

install(
DIRECTORY
launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

install(TARGETS awapi_awiv_adapter
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
endif()
Empty file.
190 changes: 190 additions & 0 deletions awapi/awapi_awiv_adapter/Readme.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,190 @@
# AWAPI_AWIV_ADAPTER

✓: confirmed, (blank): not confirmed

## get topic

### /awapi/vehicle/get/status

- get vehicle status
- MessageType: awapi_awiv_adapter/AwapiVehicleStatus

|| type | name | unit | note |
| --- | :------------------------ | :----------------------- | :-------------------------------------------- | :--------------------------------------- |
|| std_msgs/Header | header | | |
|| geometry_msgs/Pose | pose | position:[m] | |
|| awapi_awiv_adapter/Euler | eulerangle | [rad] | roll/pitch/yaw |
| | awapi_awiv_adapter/Latlon | latlon | | lat/lon/alt |
|| float64 | velocity | [m/s] | |
|| float64 | acceleration | [m/ss] | calculate from velocity in awapi_adapter |
|| float64 | steering | [rad] | |
|| float64 | steering_velocity | [rad/s] | calculate from steering in awapi_adapter |
|| float64 | angular_velocity | [rad/s] | |
| | int32 | gear | accroding to autoware_vehicle_msgs/Shift | |
| | float32 | energy_level | | available only for golf-cart |
|| int32 | turn_signal | accroding to autoware_vehicle_msgs/TurnSignal | |
|| float64 | target_velocity | [m/s] | |
|| float64 | target_acceleration | [m/ss] | |
|| float64 | target_steering | [rad] | |
|| float64 | target_steering_velocity | [rad/s] | |

### /awapi/autoware/get/status

- get autoware status
- MessageType: awapi_awiv_adapter/AwapiVehicleStatus

|| type | name | unit | note |
| --- | :------------------------------------- | :---------------- | :--------------------------------------------- | :-------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|| std_msgs/Header | header | | |
|| string | autoware_state | | |
|| int32 | control_mode | accroding to autoware_vehicle_msgs/ControlMode | manual/auto (changed by /awapi/autoware/put/engage) |
| | int32 | gate_mode | autoware_vehicle_msgs/GateMode | auto/remote (it is valid only when control_mode=auto)) |
|| bool | emergency_stopped | True in emergency mode | |
|| autoware_planning_msgs/StopReasonArray | stop_reason | | "stop_pose" represents the position of "base_link" (not the head of the car) |
|| diagnostic_msgs/DiagnosticStatus[] | diagnostics | | output only diag. of leaf node (diag. of parent node are cut) |
|| bool | arrived_goal | | True if the autoware_state is changed from Driving to ArrivedGoal or WairingForRoute. False if the autoware_state is changed to WaitingForEngage or Driving. Default False. |

### /awapi/autoware/get/route

- get route
- MessageType: autoware_planning_msgs/Route

|| type | name | unit | note |
| --- | :--------------------------- | :--- | :--- | :--- |
|| autoware_planning_msgs/Route | | | |

### /awapi/prediction/get/objects

- get predicted object
- MessageType: autoware_perception_msgs/DynamicObjectArray

|| type | name | unit | note |
| --- | :------------------------------------------ | :--- | :--- | :--- |
|| autoware_perception_msgs/DynamicObjectArray | | | |

### /awapi/lane_change/get/status

- get lane change information
- MessageType: awapi_awiv_adapter/LaneChangeStatus

|| type | name | unit | note |
| --- | :-------------------------- | :-------------------------- | :--------------------------------------- | :--------------------------------------------------------------------------------- |
| | std_msgs/Header | header | | |
| | bool | force_lane_change_available | True when lane change is avilable | available: Physically lane changeable state (do not consider other vehicle) |
| | bool | lane_change_ready | True when lane change is ready | ready: State that ego-vehicle can change lane without collision with other vehicle |
| | autoware_planning_msgs/Path | candidate_path | according to autoware_planning_msgs/Path | |

### /awapi/object_avoidance/get/status

- get obstacle avoidance information
- MessageType: awapi_awiv_adapter/ObstacleAvoidanceStatus

|| type | name | unit | note |
| --- | :-------------------------------- | :----------------------- | :--------------------------------------------- | :---------------------------------------------------- |
| | std_msgs/Header | header | | |
| | bool | obstacle_avoidance_ready | True when obstacle avoidance is ready | |
| | autoware_planning_msgs/Trajectory | candidate_path | according to autoware_planning_msgs/Trajectory | Msg type is different from lane change candidate path |

### /awapi/traffic_light/get/status

- get recognition result of traffic light
- MessageType: autoware_perception_msgs/TrafficLightStateArray

|| type | name | unit | note |
| --- | :---------------------------------------------- | :--- | :--- | :--- |
| | autoware_perception_msgs/TrafficLightStateArray | | | |

## put topic

### /awapi/vehicle/put/velocity

- set upper velocity
- MessageType: std_msgs/Float32

|| type | name | unit | note |
| --- | :--------------- | :--- | :--- | :----------- |
|| std_msgs/Float32 | | | max velocity |

### /awapi/autoware/put/gate_mode

- send gate mode (auto/remote)
- MessageType: autoware_control_msgs/GateMode

|| type | name | unit | note |
| --- | :----------------------------- | :--- | :--- | :--- |
| | autoware_control_msgs/GateMode | | | |

### /awapi/autoware/put/emergency

- send emergency signal
- MessageType: std_msgs/Bool
- <font color="Cyan">**To enable this functionality, autoware have to be in the Remote Mode or set _/control/vehicle_cmd_gate/use_emergency_handling_ to true.**</font>

|| type | name | unit | note |
| --- | :------------ | :--- | :--- | :--- |
|| std_msgs/Bool | | | |

### /awapi/autoware/put/engage

- send engage signal (both of autoware/engage and vehicle/engage)
- MessageType: std_msgs/Bool

|| type | name | unit | note |
| --- | :------------ | :--- | :--- | :--- |
|| std_msgs/Bool | | | |

### /awapi/autoware/put/route

- send goal pose
- MessageType: autoware_planning_msgs/Route

|| type | name | unit | note |
| --- | :--------------------------- | :--- | :--- | :--- |
|| autoware_planning_msgs/Route | | | |

### /awapi/lane_change/put/approval

- send lane change approval flag
- send True: start lane change when **lane_change_ready** is true
- MessageType: std_msgs/Bool

|| type | name | unit | note |
| --- | :------------ | :--- | :--- | :--- |
| | std_msgs/Bool | | | |

### /awapi/lane_change/put/force

- send force lane change flag
- send True: start lane change when **force_lane_change_available** is true
- MessageType: std_msgs/Bool

|| type | name | unit | note |
| --- | :------------ | :--- | :--- | :--- |
| | std_msgs/Bool | | | |

### /awapi/object_avoidance/put/approval

- send object avoidance approval flag
- MessageType: std_msgs/Bool

|| type | name | unit | note |
| --- | :------------ | :--- | :--- | :--- |
| | std_msgs/Bool | | | |

### /awapi/object_avoidance/put/force

- send force object avoidance flag
- <font color="Red">**not implemented (Autoware does not have corresponded topic)**</font>

|| type | name | unit | note |
| --- | :--- | :--- | :--- | :--- |


### /awapi/traffic_light/put/traffic_light

- Overwrite the recognition result of traffic light
- <font color="Red">**not implemented (Autoware does not have corresponded topic)**</font>

|| type | name | unit | note |
| --- | :--- | :--- | :--- | :--- |

Loading

0 comments on commit 4d45188

Please sign in to comment.