├── +autoware ├── LibWaypointFollower.m ├── TrafficLight.m ├── addCustomMessageFolderToSearchPath.m ├── createCustomMessages.m ├── editJavaClassPath.m └── getRootDirectory.m ├── .gitignore ├── AUTHORS ├── LICENSE ├── README.md ├── autoware_toolbox_setup.m ├── benchmark ├── computing │ ├── perception │ │ ├── detection │ │ │ ├── lidar_tracker │ │ │ │ └── lidar_euclidean_track │ │ │ │ │ └── lidar_euclidean_track_ml.m │ │ │ ├── vision_detector │ │ │ │ └── acf_detector │ │ │ │ │ ├── AcfDetector.m │ │ │ │ │ ├── acf_detector_sl.slx │ │ │ │ │ ├── acf_detector_sl.slxc │ │ │ │ │ └── v1_7 │ │ │ │ │ ├── acf_detector_ml.m │ │ │ │ │ └── acf_detector_sl.slx │ │ │ └── vision_tracker │ │ │ │ └── vision_dummy_track │ │ │ │ ├── vision_dummy_track.m │ │ │ │ ├── vision_dummy_track_sl.slx │ │ │ │ └── vision_dummy_track_sl.slx.r2018b │ │ └── localization │ │ │ └── autoware_connector │ │ │ └── vel_pose_connect │ │ │ ├── VehicleInfo.m │ │ │ ├── VelPoseConnect.m │ │ │ ├── vel_pose_connect_ml.m │ │ │ ├── vel_pose_connect_sl.slx │ │ │ ├── vel_pose_connect_sl.slx.r2018b │ │ │ └── vel_pose_connect_sl.slxc │ └── planning │ │ ├── mission │ │ └── lane_stop │ │ │ ├── LaneStop.m │ │ │ ├── lane_stop_ml.m │ │ │ ├── lane_stop_sl.slx │ │ │ ├── lane_stop_sl.slx.r2017b │ │ │ └── lane_stop_sl.slxc │ │ └── motion │ │ ├── lattice_planner │ │ └── path_select │ │ │ ├── PathSelect.m │ │ │ ├── path_select_ml.m │ │ │ ├── path_select_sl.slx │ │ │ ├── path_select_sl.slx.r2018b │ │ │ ├── path_select_sl.slxc │ │ │ └── path_select_sl2.slxc │ │ └── waypoint_follower │ │ ├── pure_pursuit │ │ ├── pure_pursuit_sl.slx │ │ ├── pure_pursuit_sl.slx.r2018b │ │ ├── pure_pursuit_sl.slxc │ │ └── twist_filter_sl.slxc │ │ ├── twist_filter │ │ ├── twist_filter_sl.slx │ │ ├── twist_filter_sl.slx.r2018b │ │ ├── twist_filter_sl.slxc │ │ └── untitled.slx.autosave │ │ ├── twist_gate │ │ ├── TwistGate.m │ │ ├── twist_filter_sl.slxc │ │ └── twist_gate_ml.m │ │ └── wf_simulator │ │ ├── WfSimulator.m │ │ └── wf_simulator_ml.m └── sensing │ └── filters │ ├── image_processor │ └── fog_rectification │ │ ├── fog_rectification.m │ │ └── fog_rectification_ml.m │ └── points_downsampler │ ├── nonuniformgrid_filter │ └── nonuniformgrid_filter_ml.m │ ├── random_filter │ └── random_filter_ml.m │ └── voxel_grid_filter │ ├── VoxelGridFilter.m │ └── voxel_grid_filter_ml.m ├── custom_msgs ├── autoware_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ │ ├── CANData.msg │ │ ├── CANPacket.msg │ │ ├── CameraExtrinsic.msg │ │ ├── CanInfo.msg │ │ ├── CloudCluster.msg │ │ ├── CloudClusterArray.msg │ │ ├── ColorSet.msg │ │ ├── ConfigApproximateNdtMapping.msg │ │ ├── ConfigCarDpm.msg │ │ ├── ConfigCarFusion.msg │ │ ├── ConfigCarKf.msg │ │ ├── ConfigDecisionMaker.msg │ │ ├── ConfigDistanceFilter.msg │ │ ├── ConfigICP.msg │ │ ├── ConfigLaneRule.msg │ │ ├── ConfigLaneSelect.msg │ │ ├── ConfigLaneStop.msg │ │ ├── ConfigLatticeVelocitySet.msg │ │ ├── ConfigNdt.msg │ │ ├── ConfigNdtMapping.msg │ │ ├── ConfigNdtMappingOutput.msg │ │ ├── ConfigPedestrianDpm.msg │ │ ├── ConfigPedestrianFusion.msg │ │ ├── ConfigPedestrianKf.msg │ │ ├── ConfigPlannerSelector.msg │ │ ├── ConfigPoints2Polygon.msg │ │ ├── ConfigRandomFilter.msg │ │ ├── ConfigRayGroundFilter.msg │ │ ├── ConfigRcnn.msg │ │ ├── ConfigRingFilter.msg │ │ ├── ConfigRingGroundFilter.msg │ │ ├── ConfigSsd.msg │ │ ├── ConfigTwistFilter.msg │ │ ├── ConfigVelocitySet.msg │ │ ├── ConfigVoxelGridFilter.msg │ │ ├── ConfigWaypointFollower.msg │ │ ├── ConfigWaypointLoader.msg │ │ ├── ControlCommand.msg │ │ ├── ControlCommandStamped.msg │ │ ├── DetectedObject.msg │ │ ├── DetectedObjectArray.msg │ │ ├── ExtractedPosition.msg │ │ ├── ImageLaneObjects.msg │ │ ├── ImageObjects.msg │ │ ├── LaneArray.msg │ │ ├── PointsImage.msg │ │ ├── RemoteCmd.msg │ │ ├── ScanImage.msg │ │ ├── Signals.msg │ │ ├── Sync_time_diff.msg │ │ ├── Sync_time_monitor.msg │ │ ├── TrafficLightResult.msg │ │ ├── TrafficLightResultArray.msg │ │ ├── TunedResult.msg │ │ ├── ValueSet.msg │ │ ├── VehicleCmd.msg │ │ ├── VehicleStatus.msg │ │ ├── WaypointState.msg │ │ ├── accel_cmd.msg │ │ ├── adjust_xy.msg │ │ ├── brake_cmd.msg │ │ ├── centroids.msg │ │ ├── dtlane.msg │ │ ├── geometric_rectangle.msg │ │ ├── icp_stat.msg │ │ ├── image_obj.msg │ │ ├── image_obj_ranged.msg │ │ ├── image_obj_tracked.msg │ │ ├── image_rect.msg │ │ ├── image_rect_ranged.msg │ │ ├── indicator_cmd.msg │ │ ├── lamp_cmd.msg │ │ ├── lane.msg │ │ ├── ndt_stat.msg │ │ ├── obj_label.msg │ │ ├── obj_pose.msg │ │ ├── projection_matrix.msg │ │ ├── state.msg │ │ ├── state_cmd.msg │ │ ├── steer_cmd.msg │ │ ├── traffic_light.msg │ │ ├── vscan_tracked.msg │ │ ├── vscan_tracked_array.msg │ │ └── waypoint.msg │ └── package.xml ├── dbw_mkz_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ │ ├── AmbientLight.msg │ │ ├── BrakeCmd.msg │ │ ├── BrakeInfoReport.msg │ │ ├── BrakeReport.msg │ │ ├── FuelLevelReport.msg │ │ ├── Gear.msg │ │ ├── GearCmd.msg │ │ ├── GearReject.msg │ │ ├── GearReport.msg │ │ ├── HillStartAssist.msg │ │ ├── Misc1Report.msg │ │ ├── ParkingBrake.msg │ │ ├── SteeringCmd.msg │ │ ├── SteeringReport.msg │ │ ├── SurroundReport.msg │ │ ├── ThrottleCmd.msg │ │ ├── ThrottleInfoReport.msg │ │ ├── ThrottleReport.msg │ │ ├── TirePressureReport.msg │ │ ├── TurnSignal.msg │ │ ├── TurnSignalCmd.msg │ │ ├── TwistCmd.msg │ │ ├── WatchdogCounter.msg │ │ ├── WheelPositionReport.msg │ │ ├── WheelSpeedReport.msg │ │ └── Wiper.msg │ └── package.xml ├── jsk_recognition_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ │ ├── Accuracy.msg │ │ ├── BoolStamped.msg │ │ ├── BoundingBox.msg │ │ ├── BoundingBoxArray.msg │ │ ├── BoundingBoxArrayWithCameraInfo.msg │ │ ├── BoundingBoxMovement.msg │ │ ├── Circle2D.msg │ │ ├── Circle2DArray.msg │ │ ├── ClassificationResult.msg │ │ ├── ClusterPointIndices.msg │ │ ├── ColorHistogram.msg │ │ ├── ColorHistogramArray.msg │ │ ├── ContactSensor.msg │ │ ├── ContactSensorArray.msg │ │ ├── DepthCalibrationParameter.msg │ │ ├── DepthErrorResult.msg │ │ ├── HeightmapConfig.msg │ │ ├── Histogram.msg │ │ ├── HistogramWithRange.msg │ │ ├── HistogramWithRangeArray.msg │ │ ├── HistogramWithRangeBin.msg │ │ ├── ICPResult.msg │ │ ├── ImageDifferenceValue.msg │ │ ├── Int32Stamped.msg │ │ ├── Label.msg │ │ ├── LabelArray.msg │ │ ├── Line.msg │ │ ├── LineArray.msg │ │ ├── ModelCoefficientsArray.msg │ │ ├── Object.msg │ │ ├── ObjectArray.msg │ │ ├── ParallelEdge.msg │ │ ├── ParallelEdgeArray.msg │ │ ├── PeoplePose.msg │ │ ├── PeoplePoseArray.msg │ │ ├── PlotData.msg │ │ ├── PlotDataArray.msg │ │ ├── PointsArray.msg │ │ ├── PolygonArray.msg │ │ ├── PosedCameraInfo.msg │ │ ├── Rect.msg │ │ ├── RectArray.msg │ │ ├── RotatedRect.msg │ │ ├── RotatedRectStamped.msg │ │ ├── Segment.msg │ │ ├── SegmentArray.msg │ │ ├── SegmentStamped.msg │ │ ├── SimpleHandle.msg │ │ ├── SimpleOccupancyGrid.msg │ │ ├── SimpleOccupancyGridArray.msg │ │ ├── SlicedPointCloud.msg │ │ ├── SnapItRequest.msg │ │ ├── SparseImage.msg │ │ ├── SparseOccupancyGrid.msg │ │ ├── SparseOccupancyGridArray.msg │ │ ├── SparseOccupancyGridCell.msg │ │ ├── SparseOccupancyGridColumn.msg │ │ ├── TimeRange.msg │ │ ├── Torus.msg │ │ ├── TorusArray.msg │ │ ├── TrackerStatus.msg │ │ ├── TrackingStatus.msg │ │ ├── VectorArray.msg │ │ └── WeightedPoseArray.msg │ ├── package.xml │ ├── sample │ │ └── sample_object_array_publisher.launch │ ├── scripts │ │ ├── object_array_publisher.py │ │ ├── people_pose_array_to_pose_array.py │ │ ├── plot_data_to_csv.py │ │ └── save_mesh_server.py │ └── srv │ │ ├── CallPolygon.srv │ │ ├── CallSnapIt.srv │ │ ├── CheckCircle.srv │ │ ├── CheckCollision.srv │ │ ├── EnvironmentLock.srv │ │ ├── EuclideanSegment.srv │ │ ├── ICPAlign.srv │ │ ├── ICPAlignWithBox.srv │ │ ├── NonMaximumSuppression.srv │ │ ├── PolygonOnEnvironment.srv │ │ ├── RobotPickupReleasePoint.srv │ │ ├── SaveMesh.srv │ │ ├── SetDepthCalibrationParameter.srv │ │ ├── SetLabels.srv │ │ ├── SetPointCloud2.srv │ │ ├── SetTemplate.srv │ │ ├── SnapFootstep.srv │ │ ├── SwitchTopic.srv │ │ ├── TowerPickUp.srv │ │ ├── TowerRobotMoveCommand.srv │ │ ├── TransformScreenpoint.srv │ │ ├── UpdateOffset.srv │ │ ├── WhiteBalance.srv │ │ └── WhiteBalancePoints.srv ├── vector_map_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ │ ├── Area.msg │ │ ├── AreaArray.msg │ │ ├── Box.msg │ │ ├── BoxArray.msg │ │ ├── CrossRoad.msg │ │ ├── CrossRoadArray.msg │ │ ├── CrossWalk.msg │ │ ├── CrossWalkArray.msg │ │ ├── Curb.msg │ │ ├── CurbArray.msg │ │ ├── CurveMirror.msg │ │ ├── CurveMirrorArray.msg │ │ ├── DTLane.msg │ │ ├── DTLaneArray.msg │ │ ├── DriveOnPortion.msg │ │ ├── DriveOnPortionArray.msg │ │ ├── Fence.msg │ │ ├── FenceArray.msg │ │ ├── GuardRail.msg │ │ ├── GuardRailArray.msg │ │ ├── Gutter.msg │ │ ├── GutterArray.msg │ │ ├── Lane.msg │ │ ├── LaneArray.msg │ │ ├── Line.msg │ │ ├── LineArray.msg │ │ ├── Node.msg │ │ ├── NodeArray.msg │ │ ├── Point.msg │ │ ├── PointArray.msg │ │ ├── Pole.msg │ │ ├── PoleArray.msg │ │ ├── RailCrossing.msg │ │ ├── RailCrossingArray.msg │ │ ├── RoadEdge.msg │ │ ├── RoadEdgeArray.msg │ │ ├── RoadMark.msg │ │ ├── RoadMarkArray.msg │ │ ├── RoadPole.msg │ │ ├── RoadPoleArray.msg │ │ ├── RoadSign.msg │ │ ├── RoadSignArray.msg │ │ ├── SideStrip.msg │ │ ├── SideStripArray.msg │ │ ├── SideWalk.msg │ │ ├── SideWalkArray.msg │ │ ├── Signal.msg │ │ ├── SignalArray.msg │ │ ├── StopLine.msg │ │ ├── StopLineArray.msg │ │ ├── StreetLight.msg │ │ ├── StreetLightArray.msg │ │ ├── UtilityPole.msg │ │ ├── UtilityPoleArray.msg │ │ ├── Vector.msg │ │ ├── VectorArray.msg │ │ ├── Wall.msg │ │ ├── WallArray.msg │ │ ├── WayArea.msg │ │ ├── WayAreaArray.msg │ │ ├── WhiteLine.msg │ │ ├── WhiteLineArray.msg │ │ ├── ZebraZone.msg │ │ └── ZebraZoneArray.msg │ └── package.xml └── visualization_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── mainpage.dox │ ├── msg │ ├── ImageMarker.msg │ ├── InteractiveMarker.msg │ ├── InteractiveMarkerControl.msg │ ├── InteractiveMarkerFeedback.msg │ ├── InteractiveMarkerInit.msg │ ├── InteractiveMarkerPose.msg │ ├── InteractiveMarkerUpdate.msg │ ├── Marker.msg │ ├── MarkerArray.msg │ └── MenuEntry.msg │ └── package.xml └── docs ├── en ├── Helper │ ├── addCustomMessageFolderToSearchPath_help_en.html │ ├── createCustomMessages_help_en.html │ ├── editJavaClassPath_help_en.html │ └── helper_functions_en.html ├── autoware_toolbox_product_page_en.html ├── awtb_functions_by_cat_en.html ├── helptoc.xml ├── helptoc_en.md ├── images │ ├── addon_explore_en.png │ ├── after_rosgenmsg_en.png │ ├── agree_license_en.png │ ├── autoware_messages_en.png │ ├── install_if_ros_custom_msg_en.png │ ├── java_heap_memory_preferences_en.png │ ├── javaclasspath_txt_en.png │ ├── run_setup_en.png │ └── third_party_software_en.png ├── info.xml ├── install_awtb_en.html ├── install_awtb_en.md ├── samples │ ├── Detection │ │ ├── acf_detector_ml_en.html │ │ ├── acf_detector_ml_en.m │ │ ├── acf_detector_ml_en.md │ │ ├── acf_detector_sl_en.html │ │ ├── acf_detector_sl_en.m │ │ ├── acf_detector_sl_en.md │ │ ├── images │ │ │ ├── AcfDetector │ │ │ │ ├── acf_detector_sl_top.png │ │ │ │ ├── add_new_pannel.png │ │ │ │ ├── click_rviz.png │ │ │ │ ├── detect_people.png │ │ │ │ ├── move_image_viewer.png │ │ │ │ ├── play_simulation.png │ │ │ │ ├── resize_image_viewer.png │ │ │ │ ├── rosgraph_acf_detector_ml.png │ │ │ │ ├── rosgraph_acf_detector_ml.svg │ │ │ │ ├── rosgraph_acf_detector_sl.png │ │ │ │ ├── rosgraph_acf_detector_sl.svg │ │ │ │ └── select_image_viewer_plugin.png │ │ │ └── set_rosbag.png │ │ ├── lidar_euclidean_track_ml_en.html │ │ ├── vision_dummy_track_ml_en.html │ │ └── vision_dummy_track_sl_en.html │ ├── Filters │ │ ├── demo_random_filter_ml_en.html │ │ ├── demo_voxel_grid_filter_ml_en.html │ │ ├── fog_rectification_ml_en.html │ │ ├── images │ │ │ ├── click_rviz.png │ │ │ ├── load_vehicle_model.png │ │ │ ├── map_tab.png │ │ │ ├── ndt_matching_app.png │ │ │ ├── replay_rosbag.png │ │ │ ├── run_autoware.png │ │ │ ├── runtime_manager.png │ │ │ ├── set_baselink_to_localizer.png │ │ │ ├── set_computing_tab.png │ │ │ ├── set_localizer_velodyne.png │ │ │ ├── set_plane_number.png │ │ │ ├── set_rosbag.png │ │ │ ├── show_rviz.png │ │ │ ├── simulation_clock_on.png │ │ │ └── voxel_grid_filter_ml │ │ │ │ ├── filtered_points.png │ │ │ │ ├── points_raw.png │ │ │ │ ├── rosgraph_voxel_grid_filter_ml.png │ │ │ │ ├── rosgraph_voxel_grid_filter_ml.svg │ │ │ │ └── show_rviz.png │ │ ├── nonuniformgrid_filter_ml_en.html │ │ ├── voxel_grid_filter_ml_en.html │ │ └── voxel_grid_filter_ml_en.md │ ├── Localization │ │ ├── images │ │ │ ├── 2D_Pose_Estimate.png │ │ │ ├── result_waypoint_follower.png │ │ │ └── vel_pose_connect │ │ │ │ ├── computing_tab.png │ │ │ │ ├── rosgraph.png │ │ │ │ ├── sl_rosgraph.png │ │ │ │ ├── sl_rosgraph.svg │ │ │ │ └── vel_pose_connect_sl_top.png │ │ ├── vel_pose_connect_ml_en.html │ │ ├── vel_pose_connect_ml_en.md │ │ ├── vel_pose_connect_sl_en.html │ │ └── vel_pose_connect_sl_en.md │ ├── Planning │ │ ├── images │ │ │ ├── 2D_Pose_Estimate.png │ │ │ ├── pure_pursuit │ │ │ │ ├── computing_tab.png │ │ │ │ ├── pure_pursuit_sl_top.png │ │ │ │ ├── rosgraph_pure_pursuit.png │ │ │ │ ├── rosgraph_pure_pursuit.svg │ │ │ │ └── wf_simulator_app.png │ │ │ ├── result_waypoint_follower.png │ │ │ ├── twist_filter │ │ │ │ ├── computing_tab.png │ │ │ │ ├── rosgraph_twist_filter.png │ │ │ │ ├── rosgraph_twist_filter.svg │ │ │ │ ├── twist_filter_sl_top.png │ │ │ │ └── wf_simulator_app.png │ │ │ ├── vel_pose_connect.png │ │ │ └── wf_simulator │ │ │ │ ├── computing_tab.png │ │ │ │ └── rosgraph.png │ │ ├── lane_stop_ml_en.html │ │ ├── lane_stop_sl_en.html │ │ ├── path_select_ml_en.html │ │ ├── path_select_sl_en.html │ │ ├── pure_pursuit_sl_en.html │ │ ├── pure_pursuit_sl_en.md │ │ ├── twist_filter_sl_en.html │ │ ├── twist_filter_sl_en.md │ │ ├── wf_simulator_ml_en.html │ │ └── wf_simulator_ml_en.md │ ├── demos.xml │ ├── demos_en.md │ └── images │ │ ├── choose_file_to_open.png │ │ ├── click_rviz.png │ │ ├── connect_ros_master.png │ │ ├── map_tab_load_vectormap_tf.png │ │ ├── rosinit.png │ │ ├── run_autoware.png │ │ ├── runtime_manager.png │ │ ├── rviz_file_open_config.png │ │ ├── setup_tab_load_vehicle_model.png │ │ ├── show_vectormap.png │ │ ├── waypoint_loader.png │ │ └── wf_simulator_app.png └── underConstruction.html └── ja ├── Helper ├── addCustomMessageFolderToSearchPath_help_ja.html ├── createCustomMessages_help_ja.html ├── editJavaClassPath_help_ja.html └── helper_functions_ja.html ├── autoware_toolbox_product_page_ja.html ├── awtb_functions_by_cat_ja.html ├── helptoc.xml ├── helptoc_ja.md ├── images ├── addon_explore.png ├── after_rosgenmsg.png ├── agree_license.png ├── autoware_messages.png ├── chk_rst_if_cstm_msg.png ├── input_password.png ├── install_if_ros_custom_msg.png ├── install_process.png ├── installed_message.png ├── java_heap_memory_preferences.png ├── javaclasspath_txt.png ├── not_installed_message.png ├── rosgenmsg.png ├── run_setup.png ├── signin_mathworks_acount.png └── third_party_software.png ├── info.xml ├── install_awtb_ja.html ├── install_awtb_ja.md ├── samples ├── Detection │ ├── acf_detector_ml_ja.html │ ├── acf_detector_ml_ja.md │ ├── acf_detector_sl_ja.html │ ├── acf_detector_sl_ja.md │ ├── images │ │ ├── AcfDetector │ │ │ ├── acf_detector_sl_top.png │ │ │ ├── add_new_pannel.png │ │ │ ├── click_rviz.png │ │ │ ├── detect_people.png │ │ │ ├── move_image_viewer.png │ │ │ ├── play_simulation.png │ │ │ ├── resize_image_viewer.png │ │ │ ├── rosgraph_acf_detector.png │ │ │ ├── rosgraph_acf_detector.svg │ │ │ ├── rosgraph_acf_detector_sl.png │ │ │ ├── rosgraph_acf_detector_sl.svg │ │ │ └── select_image_viewer_plugin.png │ │ ├── run_autoware.png │ │ ├── runtime_manager.png │ │ └── set_rosbag.png │ ├── lidar_euclidean_track_ml_ja.html │ ├── vision_dummy_track_ml_ja.html │ └── vision_dummy_track_sl_ja.html ├── Filters │ ├── demo_random_filter_ml_ja.html │ ├── demo_voxel_grid_filter_ml_ja.html │ ├── fog_rectification_ml_ja.html │ ├── images │ │ ├── click_rviz.png │ │ ├── load_vehicle_model.png │ │ ├── map_tab.png │ │ ├── ndt_matching_app.png │ │ ├── replay_rosbag.png │ │ ├── run_autoware.png │ │ ├── runtime_manager.png │ │ ├── select_rosbag_file.png │ │ ├── set_baselink_to_localizer.png │ │ ├── set_computing_tab.png │ │ ├── set_localizer_velodyne.png │ │ ├── set_plane_number.png │ │ ├── set_rosbag.png │ │ ├── set_rosbag2.png │ │ ├── show_rviz.png │ │ ├── simulation_clock_on.png │ │ └── voxel_grid_filter_ml │ │ │ ├── filtered_points.png │ │ │ ├── points_raw.png │ │ │ ├── rosgraph_voxel_grid_filter_ml.png │ │ │ ├── rosgraph_voxel_grid_filter_ml.svg │ │ │ └── show_rviz.png │ ├── nonuniformgrid_filter_ml_ja.html │ ├── voxel_grid_filter_ml_ja.html │ ├── voxel_grid_filter_ml_ja.m │ └── voxel_grid_filter_ml_ja.md ├── Localization │ ├── images │ │ ├── 2D_Pose_Estimate.png │ │ ├── result_waypoint_follower.png │ │ ├── rosinit.png │ │ └── vel_pose_connect │ │ │ ├── computing_tab.png │ │ │ ├── rosgraph.png │ │ │ ├── rosgraph.svg │ │ │ ├── run_vel_pose_connect.png │ │ │ ├── sl_rosgraph.png │ │ │ ├── sl_rosgraph.svg │ │ │ └── vel_pose_connect_sl_top.PNG │ ├── vel_pose_connect_ml_ja.html │ ├── vel_pose_connect_ml_ja.md │ ├── vel_pose_connect_sl_ja.html │ └── vel_pose_connect_sl_ja.md ├── Planning │ ├── images │ │ ├── 2D_Pose_Estimate.png │ │ ├── pure_pursuit │ │ │ ├── computing_tab.png │ │ │ ├── pure_pursuit_sl_top.png │ │ │ ├── rosgraph_pure_pursuit.png │ │ │ ├── rosgraph_pure_pursuit.svg │ │ │ └── wf_simulator_app.png │ │ ├── result_waypoint_follower.png │ │ ├── twist_filter │ │ │ ├── computing_tab.png │ │ │ ├── rosgraph_twist_filter.png │ │ │ ├── rosgraph_twist_filter.svg │ │ │ ├── twist_filter_sl_top.png │ │ │ └── wf_simulator_app.png │ │ ├── vel_pose_connect.png │ │ └── wf_simulator │ │ │ ├── computing_tab.png │ │ │ └── rosgraph.png │ ├── lane_stop_ml_ja.html │ ├── lane_stop_sl_ja.html │ ├── path_select_ml_ja.html │ ├── path_select_sl_ja.html │ ├── pure_pursuit_sl_ja.html │ ├── pure_pursuit_sl_ja.md │ ├── twist_filter_sl_ja.html │ ├── twist_filter_sl_ja.md │ ├── wf_simulator_ml_ja.html │ └── wf_simulator_ml_ja.md ├── demos.xml ├── demos_ja.md └── images │ ├── choose_file_to_open.png │ ├── click_rviz.png │ ├── connect_ros_master.png │ ├── map_tab_load_vectormap_tf.png │ ├── rosinit.png │ ├── run_autoware.png │ ├── runtime_manager.png │ ├── rviz_file_open_config.png │ ├── setup_tab_load_vehicle_model.png │ ├── show_vectormap.png │ ├── waypoint_loader.png │ └── wf_simulator_app.png └── underConstruction.html /+autoware/LibWaypointFollower.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/+autoware/LibWaypointFollower.m -------------------------------------------------------------------------------- /+autoware/TrafficLight.m: -------------------------------------------------------------------------------- 1 | classdef TrafficLight < uint32 2 | enumeration 3 | RED (0) 4 | GREEN (1) 5 | UNKNOWN (2) 6 | end 7 | end 8 | % [EOF] -------------------------------------------------------------------------------- /+autoware/addCustomMessageFolderToSearchPath.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/+autoware/addCustomMessageFolderToSearchPath.m -------------------------------------------------------------------------------- /+autoware/createCustomMessages.m: -------------------------------------------------------------------------------- 1 | function [] = createCustomMessages() 2 | % 3 | % Create custom messages from ROS definitions. 4 | % 5 | % -- 6 | % Autor(s): Noriyuki OTA, March 25, 2019 7 | % Copyright 2019 NEXTY Electronics Corporation 8 | % 9 | 10 | msg_folder_path = fullfile(autoware.getRootDirectory(), 'custom_msgs'); 11 | rosgenmsg(msg_folder_path); 12 | 13 | % [EOF] -------------------------------------------------------------------------------- /+autoware/editJavaClassPath.m: -------------------------------------------------------------------------------- 1 | function [] = editJavaClassPath() 2 | % 3 | % Edit javaclasspath.txt, add the jar file locations as new lines, and save the file. 4 | % 5 | % -- 6 | % Autor(s): Noriyuki OTA, March 25, 2019 7 | % Copyright 2019 NEXTY Electronics Corporation 8 | % 9 | 10 | mfile_path = fileparts(mfilename('fullpath')); 11 | custom_msgs_folder = fullfile(mfile_path(1:end-length('+autoware')), 'custom_msgs', 'matlab_gen'); 12 | jar_folder = fullfile(custom_msgs_folder, 'jar'); 13 | jar_file_locations{1} = fullfile(jar_folder, 'autoware_msgs-1.8.0.jar'); 14 | jar_file_locations{2} = fullfile(jar_folder, 'dbw_mkz_msgs-1.8.0.jar'); 15 | jar_file_locations{3} = fullfile(jar_folder, 'jsk_recognition_msgs-1.2.5.jar'); 16 | jar_file_locations{4} = fullfile(jar_folder, 'vector_map_msgs-1.8.0.jar'); 17 | jar_file_locations{5} = fullfile(jar_folder, 'visualization_msgs-1.12.7.jar'); 18 | 19 | javaclasspath_txt = fullfile(prefdir(), 'javaclasspath.txt'); 20 | type = exist(javaclasspath_txt, 'file'); 21 | if type ~= 2 22 | fmt = sprintf('%%s\n'); 23 | new_file = [{''}, jar_file_locations]; 24 | else 25 | fmt = sprintf('\n%%s'); 26 | A = importdata(javaclasspath_txt); 27 | new_file = setdiff(jar_file_locations, A); 28 | end 29 | fid = fopen(javaclasspath_txt, 'a+'); 30 | c = onCleanup(@() fclose(fid)); 31 | fprintf(fid, fmt, new_file{:}); 32 | edit(javaclasspath_txt); 33 | 34 | % [EOF] -------------------------------------------------------------------------------- /+autoware/getRootDirectory.m: -------------------------------------------------------------------------------- 1 | function awtb_root = getRootDirectory() 2 | % GETROOTDIRECTORY Get the root directory of Autoware Toolbox. 3 | % 4 | % -- 5 | % Autor(s): Noriyuki OTA, April 25, 2019 6 | % Copyright 2019 NEXTY Electronics Corporation 7 | % 8 | 9 | mfile_path = fileparts(mfilename('fullpath')); 10 | awtb_root = mfile_path(1:end-length('\+autoware')); 11 | 12 | % [EOF] -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # macOS 2 | .DS_Store 3 | 4 | # Simulink 5 | slprj/ 6 | 7 | # Autoware Toolbox 8 | custom_msgs/matlab_gen/ 9 | docs/ja/helpsearch-v3/ -------------------------------------------------------------------------------- /AUTHORS: -------------------------------------------------------------------------------- 1 | Developers 2 | ---------- 3 | Shota Tokunaga, Osaka Univercity 4 | Noriyuki Ota, NEXTY Electronics Corporation 5 | Yoshiharu Tange, NEXTY Electronics Corporation 6 | Keita Miura, Saitama University 7 | Takuya Azumi, Saitama University 8 | 9 | Contact 10 | ------- 11 | Noriyuki Ota 12 | Takuya Azumi / -------------------------------------------------------------------------------- /autoware_toolbox_setup.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/autoware_toolbox_setup.m -------------------------------------------------------------------------------- /benchmark/computing/perception/detection/vision_detector/acf_detector/AcfDetector.m: -------------------------------------------------------------------------------- 1 | classdef AcfDetector < handle 2 | %AcfDetector Detecting people using aggregate channel features (ACF). 3 | 4 | properties (Access = private) 5 | node 6 | sub_acf_detector 7 | pub_acf_detector 8 | detector 9 | end 10 | 11 | methods 12 | function obj = AcfDetector() 13 | %AcfDetector Construct a AcfDetector object 14 | % 15 | obj.node = robotics.ros.Node('acf_detector_ml'); 16 | obj.sub_acf_detector = robotics.ros.Subscriber(obj.node, '/image_raw', 'sensor_msgs/Image', @obj.callbackAcfDetector); 17 | obj.pub_acf_detector = robotics.ros.Publisher(obj.node, '/detection/vision_objects', 'autoware_msgs/DetectedObjectArray'); 18 | obj.detector = peopleDetectorACF('inria'); 19 | end 20 | 21 | function delete(obj) %#ok 22 | disp('Delete AcfDetector object.'); 23 | end 24 | end 25 | 26 | methods (Access = private) 27 | function [] = callbackAcfDetector(obj, sub, image_source) %#ok 28 | % callbackAcfDetector Callback that runs when the subscriber object handle receives a topic message 29 | msg = rosmessage('autoware_msgs/DetectedObjectArray'); 30 | msg.Header = image_source.Header; 31 | I = image_source.readImage(); 32 | [bboxes, scores] = obj.detector.detect(I); 33 | if ~isempty(bboxes) 34 | num = size(bboxes); 35 | j = 1; 36 | for i = 1 : num(1) 37 | detected_object = robotics.ros.custom.msggen.autoware_msgs.DetectedObject(); 38 | if scores(i) > 15 39 | detected_object.Label = 'Person'; 40 | detected_object.X = bboxes(i, 1); 41 | detected_object.Y = bboxes(i, 2); 42 | detected_object.Height = bboxes(i, 4); 43 | detected_object.Width = bboxes(i, 3); 44 | detected_object.Score = scores(i); 45 | msg.Objects(j) = detected_object; 46 | j = j + 1; 47 | end 48 | end 49 | end 50 | obj.pub_acf_detector.send(msg); 51 | end 52 | end 53 | end 54 | 55 | -------------------------------------------------------------------------------- /benchmark/computing/perception/detection/vision_detector/acf_detector/acf_detector_sl.slx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/perception/detection/vision_detector/acf_detector/acf_detector_sl.slx -------------------------------------------------------------------------------- /benchmark/computing/perception/detection/vision_detector/acf_detector/acf_detector_sl.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/perception/detection/vision_detector/acf_detector/acf_detector_sl.slxc -------------------------------------------------------------------------------- /benchmark/computing/perception/detection/vision_detector/acf_detector/v1_7/acf_detector_ml.m: -------------------------------------------------------------------------------- 1 | global detector; 2 | global pub_acf_detector; 3 | 4 | node = robotics.ros.Node('acf_detector_ml'); 5 | pub_acf_detector =robotics.ros.Publisher(node, '/obj_person/image_obj', 'autoware_msgs/image_obj'); 6 | sub = robotics.ros.Subscriber(node, '/image_raw', 'sensor_msgs/Image', @callback_acf_detector); 7 | 8 | detector = peopleDetectorACF('inria'); 9 | 10 | function callback_acf_detector(~, image_source) 11 | global detector; 12 | global pub_acf_detector; 13 | msg = rosmessage('autoware_msgs/image_obj'); 14 | 15 | msg.Header = image_source.Header; 16 | msg.Type = 'Person'; 17 | 18 | I = readImage(image_source); 19 | [bboxes, scores] = detect(detector, I); 20 | 21 | if ~isempty(bboxes) 22 | num = size(bboxes); 23 | j = 1; 24 | for i = 1 : num(1) 25 | image_rect = robotics.ros.custom.msggen.autoware_msgs.image_rect; 26 | if scores(i) > 15 27 | image_rect.X = bboxes(i, 1); 28 | image_rect.Y = bboxes(i, 2); 29 | image_rect.Height = bboxes(i, 4); 30 | image_rect.Width = bboxes(i, 3); 31 | image_rect.Score = scores(i); 32 | msg.Obj(j) = image_rect; 33 | j = j + 1; 34 | end 35 | end 36 | end 37 | send(pub_acf_detector, msg); 38 | end -------------------------------------------------------------------------------- /benchmark/computing/perception/detection/vision_detector/acf_detector/v1_7/acf_detector_sl.slx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/perception/detection/vision_detector/acf_detector/v1_7/acf_detector_sl.slx -------------------------------------------------------------------------------- /benchmark/computing/perception/detection/vision_tracker/vision_dummy_track/vision_dummy_track.m: -------------------------------------------------------------------------------- 1 | global pub_image_obj_tracked 2 | 3 | % car: flag == 1, person = flag == 0 4 | flag = 1; 5 | if flag ==1 6 | node_name = 'obj_car/dummy_track_ml'; 7 | pub_topic = '/obj_car/image_obj_tracked'; 8 | sub_topic = '/obj_car/image_obj_ranged'; 9 | else 10 | node_name = 'obj_car/dummy_track_ml'; 11 | pub_topic = '/obj_person/image_obj_tracked'; 12 | sub_topic = '/obj_person/image_obj_ranged'; 13 | end 14 | 15 | node = robotics.ros.Node(node_name); 16 | pub_image_obj_tracked =robotics.ros.Publisher(node, pub_topic, 'autoware_msgs/image_obj_tracked'); 17 | sub_image_obj_ranged = robotics.ros.Subscriber(node, sub_topic, 'autoware_msgs/image_obj_ranged', @callback_image_obj_ranged); 18 | 19 | 20 | function callback_image_obj_ranged(~, image_objects_msg) 21 | global pub_image_obj_tracked 22 | 23 | msg = rosmessage('autoware_msgs/image_obj_tracked'); 24 | msg.Header = image_objects_msg.Header; 25 | msg.Type = image_objects_msg.Type; 26 | msg.RectRanged = image_objects_msg.Obj; 27 | num = size(image_objects_msg.Obj); 28 | msg.TotalNum = num(1); 29 | for i = 1 : msg.TotalNum 30 | msg.ObjId(i) = i; 31 | msg.RealData(i) = 0; 32 | msg.Lifespan(i) = 45; 33 | end 34 | send(pub_image_obj_tracked, msg); 35 | end -------------------------------------------------------------------------------- /benchmark/computing/perception/detection/vision_tracker/vision_dummy_track/vision_dummy_track_sl.slx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/perception/detection/vision_tracker/vision_dummy_track/vision_dummy_track_sl.slx -------------------------------------------------------------------------------- /benchmark/computing/perception/detection/vision_tracker/vision_dummy_track/vision_dummy_track_sl.slx.r2018b: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/perception/detection/vision_tracker/vision_dummy_track/vision_dummy_track_sl.slx.r2018b -------------------------------------------------------------------------------- /benchmark/computing/perception/localization/autoware_connector/vel_pose_connect/VehicleInfo.m: -------------------------------------------------------------------------------- 1 | classdef VehicleInfo 2 | properties 3 | is_stored = false; 4 | wheel_base = 0.0; 5 | minimum_turning_radius = 0.0; 6 | maximum_steering_angle = 0.0; 7 | end 8 | 9 | methods 10 | end 11 | end 12 | % [EOF] -------------------------------------------------------------------------------- /benchmark/computing/perception/localization/autoware_connector/vel_pose_connect/vel_pose_connect_sl.slx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/perception/localization/autoware_connector/vel_pose_connect/vel_pose_connect_sl.slx -------------------------------------------------------------------------------- /benchmark/computing/perception/localization/autoware_connector/vel_pose_connect/vel_pose_connect_sl.slx.r2018b: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/perception/localization/autoware_connector/vel_pose_connect/vel_pose_connect_sl.slx.r2018b -------------------------------------------------------------------------------- /benchmark/computing/perception/localization/autoware_connector/vel_pose_connect/vel_pose_connect_sl.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/perception/localization/autoware_connector/vel_pose_connect/vel_pose_connect_sl.slxc -------------------------------------------------------------------------------- /benchmark/computing/planning/mission/lane_stop/lane_stop_sl.slx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/mission/lane_stop/lane_stop_sl.slx -------------------------------------------------------------------------------- /benchmark/computing/planning/mission/lane_stop/lane_stop_sl.slx.r2017b: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/mission/lane_stop/lane_stop_sl.slx.r2017b -------------------------------------------------------------------------------- /benchmark/computing/planning/mission/lane_stop/lane_stop_sl.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/mission/lane_stop/lane_stop_sl.slxc -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/lattice_planner/path_select/PathSelect.m: -------------------------------------------------------------------------------- 1 | rosclassdef PathSelect < handle 2 | % PathSelect Generating final waypoints from temporal waypoints.. 3 | % 4 | 5 | properties (Access = private) 6 | node; 7 | pub_final_waypoints; 8 | sub_temporal_waypoints; 9 | end 10 | 11 | methods 12 | function obj = PathSelect() 13 | % PathSelect Construct a PathSelect object 14 | % 15 | 16 | % --- Initialize the ROS node --- 17 | obj.node = robotics.ros.Node('paht_select_ml'); 18 | % --- Creates publisher --- 19 | obj.pub_final_waypoints = ... 20 | robotics.ros.Publisher(obj.node, '/final_waypoints', 'autoware_msgs/lane'); 21 | % --- Creates subscriber --- 22 | obj.sub_temporal_waypoints = ... 23 | robotics.ros.Subscriber(obj.node, '/temporal_waypoints', 'autoware_msgs/lane', ... 24 | @obj.temporal_waypoints_callback); 25 | end 26 | 27 | function delete(obj) %#ok 28 | disp('Delete PathSelect object.'); 29 | end 30 | end 31 | 32 | methods (Access = private) 33 | function [] = temporal_waypoints_callback(obj, sub, msg) %#ok 34 | obj.pub_final_waypoints.send(msg) 35 | end 36 | end 37 | end 38 | % [EOF] -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/lattice_planner/path_select/path_select_ml.m: -------------------------------------------------------------------------------- 1 | global pub_final_waypoints; 2 | 3 | node = robotics.ros.Node('paht_select_ml'); 4 | pub_final_waypoints = robotics.ros.Publisher(node, '/final_waypoints', 'autoware_msgs/lane'); 5 | sub_temporal_waypoints = robotics.ros.Subscriber(node, '/base_waypoints', 'autoware_msgs/lane', @temporal_waypoints_callback); 6 | 7 | function temporal_waypoints_callback(~, msg) 8 | global pub_final_waypoints; 9 | 10 | send(pub_final_waypoints, msg) 11 | end -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/lattice_planner/path_select/path_select_sl.slx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/lattice_planner/path_select/path_select_sl.slx -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/lattice_planner/path_select/path_select_sl.slx.r2018b: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/lattice_planner/path_select/path_select_sl.slx.r2018b -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/lattice_planner/path_select/path_select_sl.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/lattice_planner/path_select/path_select_sl.slxc -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/lattice_planner/path_select/path_select_sl2.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/lattice_planner/path_select/path_select_sl2.slxc -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/pure_pursuit/pure_pursuit_sl.slx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/pure_pursuit/pure_pursuit_sl.slx -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/pure_pursuit/pure_pursuit_sl.slx.r2018b: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/pure_pursuit/pure_pursuit_sl.slx.r2018b -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/pure_pursuit/pure_pursuit_sl.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/pure_pursuit/pure_pursuit_sl.slxc -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/pure_pursuit/twist_filter_sl.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/pure_pursuit/twist_filter_sl.slxc -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/twist_filter/twist_filter_sl.slx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/twist_filter/twist_filter_sl.slx -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/twist_filter/twist_filter_sl.slx.r2018b: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/twist_filter/twist_filter_sl.slx.r2018b -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/twist_filter/twist_filter_sl.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/twist_filter/twist_filter_sl.slxc -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/twist_filter/untitled.slx.autosave: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/twist_filter/untitled.slx.autosave -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/twist_gate/TwistGate.m: -------------------------------------------------------------------------------- 1 | classdef TwistGate < handle 2 | 3 | properties (Access=private) 4 | node 5 | vehicle_cmd_pub 6 | auto_cmd_sub 7 | twist_gate_msg 8 | end 9 | 10 | methods (Access=public) 11 | function obj = TwistGate() 12 | obj.node = robotics.ros.Node('twist_gate_ml'); 13 | obj.vehicle_cmd_pub = robotics.ros.Publisher(obj.node, '/vehicle_cmd', 'autoware_msgs/VehicleCmd'); 14 | obj.auto_cmd_sub = containers.Map('KeyType', 'char', 'ValueType', 'any'); 15 | obj.auto_cmd_sub('twist_cmd') = robotics.ros.Subscriber(obj.node, '/twist_cmd', 'geometry_msgs/TwistStamped', @obj.autoCmdTwistCmdCallback); 16 | obj.twist_gate_msg = rosmessage('autoware_msgs/VehicleCmd'); 17 | obj.twist_gate_msg.Header.Seq = 0; 18 | end 19 | 20 | function delete(obj) %#ok 21 | end 22 | end 23 | 24 | methods (Access=private) 25 | function autoCmdTwistCmdCallback(obj, sub, msg) %#ok 26 | obj.twist_gate_msg.Header.FrameId = msg.Header.FrameId; 27 | obj.twist_gate_msg.Header.Stamp = msg.Header.Stamp; 28 | obj.twist_gate_msg.Header.Seq = obj.twist_gate_msg.Header.Seq + 1; 29 | obj.twist_gate_msg.TwistCmd.Twist = msg.Twist; 30 | send(obj.vehicle_cmd_pub, obj.twist_gate_msg); 31 | end 32 | end 33 | end 34 | -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/twist_gate/twist_filter_sl.slxc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/benchmark/computing/planning/motion/waypoint_follower/twist_gate/twist_filter_sl.slxc -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/twist_gate/twist_gate_ml.m: -------------------------------------------------------------------------------- 1 | % rosshutdown 2 | % rosinit 3 | 4 | twist_gate_ml_obj = TwistGate(); 5 | 6 | % delete(twist_gate_ml_obj) 7 | % clear 8 | -------------------------------------------------------------------------------- /benchmark/computing/planning/motion/waypoint_follower/wf_simulator/wf_simulator_ml.m: -------------------------------------------------------------------------------- 1 | % rosshutdown 2 | % rosinit 3 | 4 | wf_simulator_ml_obj = WfSimulator(); 5 | wf_simulator_ml_obj.run(); 6 | 7 | % delete(wf_simulator_ml_obj) 8 | % clear 9 | -------------------------------------------------------------------------------- /benchmark/sensing/filters/image_processor/fog_rectification/fog_rectification.m: -------------------------------------------------------------------------------- 1 | function [out]=fog_rectification(input) 2 | 3 | restoreOut = zeros(size(input),'double'); 4 | 5 | input = double(input)./255; 6 | 7 | 8 | darkChannel = min(input,[],3); 9 | 10 | diff_im = 0.9*darkChannel; 11 | num_iter = 3; 12 | 13 | hN = [0.0625 0.1250 0.0625; 0.1250 0.2500 0.1250; 0.0625 0.1250 0.0625]; 14 | hN = double(hN); 15 | 16 | for t = 1:num_iter 17 | diff_im = conv2(diff_im,hN,'same'); 18 | end 19 | 20 | diff_im = min(darkChannel,diff_im); 21 | diff_im = 0.6*diff_im ; 22 | 23 | factor=1.0./(1.0-(diff_im)); 24 | restoreOut(:,:,1)= (input(:,:,1)-diff_im).*factor; 25 | restoreOut(:,:,2)= (input(:,:,2)-diff_im).*factor; 26 | restoreOut(:,:,3)= (input(:,:,3)-diff_im).*factor; 27 | restoreOut=uint8(255.*restoreOut); 28 | restoreOut=uint8(restoreOut); 29 | 30 | 31 | p=5; 32 | im_gray=rgb2gray(restoreOut); 33 | [row,col]=size(im_gray); 34 | 35 | [count,~]=imhist(im_gray); 36 | prob=count'/(row*col); 37 | 38 | cdf=cumsum(prob(:)); 39 | 40 | i1=length(find(cdf<=(p/100))); 41 | i2=255-length(find(cdf>=1-(p/100))); 42 | 43 | o1=floor(255*.10); 44 | o2=floor(255*.90); 45 | 46 | t1=(o1/i1)*[0:i1]; 47 | t2=(((o2-o1)/(i2-i1))*[i1+1:i2])-(((o2-o1)/(i2-i1))*i1)+o1; 48 | t3=(((255-o2)/(255-i2))*[i2+1:255])-(((255-o2)/(255-i2))*i2)+o2; 49 | 50 | T=(floor([t1 t2 t3])); 51 | 52 | restoreOut(restoreOut == 0) = 1; 53 | 54 | u1=(restoreOut(:,:,1)); 55 | u2=(restoreOut(:,:,2)); 56 | u3=(restoreOut(:,:,3)); 57 | 58 | out1=T(u1); 59 | out2=T(u2); 60 | out3=T(u3); 61 | 62 | out = zeros([size(out1),3], 'uint8'); 63 | out(:,:,1) = uint8(out1); 64 | out(:,:,2) = uint8(out2); 65 | out(:,:,3) = uint8(out3); 66 | return -------------------------------------------------------------------------------- /benchmark/sensing/filters/image_processor/fog_rectification/fog_rectification_ml.m: -------------------------------------------------------------------------------- 1 | global pub_fog_rectification; 2 | 3 | 4 | node = robotics.ros.Node('fog_rectification_ml'); 5 | pub_fog_rectification =robotics.ros.Publisher(node, '/image_raw/rec_fog', 'sensor_msgs/Image'); 6 | sub = robotics.ros.Subscriber(node, '/image_raw', 'sensor_msgs/Image', @callback_fog_rectification); 7 | 8 | function callback_fog_rectification(~, image_source) 9 | global pub_fog_rectification 10 | 11 | image_fog = readImage(image_source); 12 | image_rect = fog_rectification(image_fog); 13 | 14 | msg = rosmessage('sensor_msgs/Image'); 15 | msg.Encoding = 'rgb8'; 16 | writeImage(msg, image_rect); 17 | send(pub_fog_rectification, msg); 18 | end -------------------------------------------------------------------------------- /benchmark/sensing/filters/points_downsampler/nonuniformgrid_filter/nonuniformgrid_filter_ml.m: -------------------------------------------------------------------------------- 1 | global pub_nonuniformgrid_filter 2 | 3 | node_nonuniformgrid_filter = robotics.ros.Node('nonuniformgrid_filter_ml'); 4 | sub_nonuniformgrid_filter = robotics.ros.Subscriber(node_nonuniformgrid_filter, '/points_raw', 'sensor_msgs/PointCloud2', @nonuniformgrid_filter_callback); 5 | pub_nonuniformgrid_filter = robotics.ros.Publisher(node_nonuniformgrid_filter, '/filtered_points', 'sensor_msgs/PointCloud2'); 6 | 7 | 8 | function nonuniformgrid_filter_callback(~, msg) 9 | global pub_nonuniformgrid_filter 10 | ptCloud = pointCloud(readXYZ(msg), 'intensity', readField(msg, 'intensity')); 11 | ptCloud.Color = cast(horzcat(ptCloud.Intensity, ptCloud.Intensity, ptCloud.Intensity), 'uint8'); 12 | 13 | maxNumPoints = 6.0; 14 | filtered_ptCloud = pcdownsample(ptCloud, 'gridAverage', maxNumPoints); 15 | filtered_ptCloud.Intensity = cast(filtered_ptCloud.Color(:, 1), 'single'); 16 | 17 | ptMsg = PointCloudToPointCloud2(filtered_ptCloud); 18 | send(pub_nonuniformgrid_filter, ptMsg); 19 | 20 | function ptMsg = PointCloudToPointCloud2(filtered_ptCloud) 21 | ptMsg = rosmessage('sensor_msgs/PointCloud2'); 22 | ptMsg.Header = msg.Header; 23 | % ptMsg.Height = size(filtered_ptCloud.Location,1); 24 | % ptMsg.Width = size(filtered_ptCloud.Location,2); 25 | ptMsg.Height = 1;inputinput 26 | ptMsg.Width = size(filtered_ptCloud.Location,1); 27 | ptMsg.PointStep = 32; 28 | ptMsg.RowStep = ptMsg.Width * ptMsg.PointStep; 29 | for k = 1:4 30 | ptMsg.Fields(k) = rosmessage('sensor_msgs/PointField'); 31 | end 32 | ptMsg.Fields(1).Name = 'x'; 33 | ptMsg.Fields(1).Offset = 0; 34 | ptMsg.Fields(1).Datatype = 7; 35 | ptMsg.Fields(1).Count = 1; 36 | ptMsg.Fields(2).Name = 'y'; 37 | ptMsg.Fields(2).Offset = 4; 38 | ptMsg.Fields(2).Datatype = 7; 39 | ptMsg.Fields(2).Count = 1; 40 | ptMsg.Fields(3).Name = 'z'; 41 | ptMsg.Fields(3).Offset = 8; 42 | ptMsg.Fields(3).Datatype = 7; 43 | ptMsg.Fields(3).Count = 1; 44 | ptMsg.Fields(4).Name = 'intensity'; 45 | ptMsg.Fields(4).Offset = 16; 46 | ptMsg.Fields(4).Datatype = 7; 47 | ptMsg.Fields(4).Count = 1; 48 | 49 | locs = reshape(filtered_ptCloud.Location,[],3); 50 | intensities = reshape(filtered_ptCloud.Intensity,[],1); 51 | data = [locs zeros(size(locs,1),1,'single') intensities zeros(size(locs,1),3,'single')]; 52 | dataPacked = reshape(permute(data,[2 1]),[],1); 53 | dataCasted = typecast(dataPacked,'uint8'); 54 | ptMsg.Data = dataCasted; 55 | end 56 | end -------------------------------------------------------------------------------- /benchmark/sensing/filters/points_downsampler/random_filter/random_filter_ml.m: -------------------------------------------------------------------------------- 1 | global pub_random_filter 2 | 3 | node_random_filter = robotics.ros.Node('random_filter_ml'); 4 | sub_random_filter = robotics.ros.Subscriber(node_random_filter, '/points_raw', 'sensor_msgs/PointCloud2', @random_callback); 5 | pub_random_filter = robotics.ros.Publisher(node_random_filter, '/filtered_points', 'sensor_msgs/PointCloud2'); 6 | 7 | 8 | function random_callback(~, msg) 9 | global pub_random_filter 10 | ptCloud = pointCloud(readXYZ(msg), 'intensity', readField(msg, 'intensity')); 11 | ptCloud.Color = cast(horzcat(ptCloud.Intensity, ptCloud.Intensity, ptCloud.Intensity), 'uint8'); 12 | 13 | percentage = 0.1; 14 | filtered_ptCloud = pcdownsample(ptCloud, 'random', percentage); 15 | filtered_ptCloud.Intensity = cast(filtered_ptCloud.Color(:, 1), 'single'); 16 | 17 | ptMsg = PointCloudToPointCloud2(filtered_ptCloud); 18 | send(pub_random_filter, ptMsg); 19 | 20 | function ptMsg = PointCloudToPointCloud2(filtered_ptCloud) 21 | ptMsg = rosmessage('sensor_msgs/PointCloud2'); 22 | ptMsg.Header = msg.Header; 23 | % ptMsg.Height = size(filtered_ptCloud.Location,1); 24 | % ptMsg.Width = size(filtered_ptCloud.Location,2); 25 | ptMsg.Height = 1; 26 | ptMsg.Width = size(filtered_ptCloud.Location,1); 27 | ptMsg.PointStep = 32; 28 | ptMsg.RowStep = ptMsg.Width * ptMsg.PointStep; 29 | for k = 1:4 30 | ptMsg.Fields(k) = rosmessage('sensor_msgs/PointField'); 31 | end 32 | ptMsg.Fields(1).Name = 'x'; 33 | ptMsg.Fields(1).Offset = 0; 34 | ptMsg.Fields(1).Datatype = 7; 35 | ptMsg.Fields(1).Count = 1; 36 | ptMsg.Fields(2).Name = 'y'; 37 | ptMsg.Fields(2).Offset = 4; 38 | ptMsg.Fields(2).Datatype = 7; 39 | ptMsg.Fields(2).Count = 1; 40 | ptMsg.Fields(3).Name = 'z'; 41 | ptMsg.Fields(3).Offset = 8; 42 | ptMsg.Fields(3).Datatype = 7; 43 | ptMsg.Fields(3).Count = 1; 44 | ptMsg.Fields(4).Name = 'intensity'; 45 | ptMsg.Fields(4).Offset = 16; 46 | ptMsg.Fields(4).Datatype = 7; 47 | ptMsg.Fields(4).Count = 1; 48 | 49 | locs = reshape(filtered_ptCloud.Location,[],3); 50 | intensities = reshape(filtered_ptCloud.Intensity,[],1); 51 | data = [locs zeros(size(locs,1),1,'single') intensities zeros(size(locs,1),3,'single')]; 52 | dataPacked = reshape(permute(data,[2 1]),[],1); 53 | dataCasted = typecast(dataPacked,'uint8'); 54 | ptMsg.Data = dataCasted; 55 | end 56 | end -------------------------------------------------------------------------------- /benchmark/sensing/filters/points_downsampler/voxel_grid_filter/voxel_grid_filter_ml.m: -------------------------------------------------------------------------------- 1 | global pub_voxel_grid_filter 2 | 3 | node_voxel_grid_filter = robotics.ros.Node('voxel_grid_filter_ml'); 4 | sub_voxel_grid_filter = robotics.ros.Subscriber(node_voxel_grid_filter, '/points_raw', 'sensor_msgs/PointCloud2', @voxel_grid_filter_callback); 5 | pub_voxel_grid_filter = robotics.ros.Publisher(node_voxel_grid_filter, '/filtered_points', 'sensor_msgs/PointCloud2'); 6 | 7 | 8 | function voxel_grid_filter_callback(~, msg) 9 | global pub_voxel_grid_filter 10 | ptCloud = pointCloud(readXYZ(msg), 'intensity', readField(msg, 'intensity')); 11 | ptCloud.Color = cast(horzcat(ptCloud.Intensity, ptCloud.Intensity, ptCloud.Intensity), 'uint8'); 12 | 13 | % gridStep is voxelsize [m] 14 | gridStep = 2.0; 15 | filtered_ptCloud = pcdownsample(ptCloud, 'gridAverage', gridStep); 16 | filtered_ptCloud.Intensity = cast(filtered_ptCloud.Color(:, 1), 'single'); 17 | 18 | ptMsg = PointCloudToPointCloud2(filtered_ptCloud); 19 | send(pub_voxel_grid_filter, ptMsg); 20 | 21 | function ptMsg = PointCloudToPointCloud2(filtered_ptCloud) 22 | ptMsg = rosmessage('sensor_msgs/PointCloud2'); 23 | ptMsg.Header = msg.Header; 24 | % ptMsg.Height = size(filtered_ptCloud.Location,1); 25 | % ptMsg.Width = size(filtered_ptCloud.Location,2); 26 | ptMsg.Height = 1; 27 | ptMsg.Width = size(filtered_ptCloud.Location,1); 28 | ptMsg.PointStep = 32; 29 | ptMsg.RowStep = ptMsg.Width * ptMsg.PointStep; 30 | for k = 1:4 31 | ptMsg.Fields(k) = rosmessage('sensor_msgs/PointField'); 32 | end 33 | ptMsg.Fields(1).Name = 'x'; 34 | ptMsg.Fields(1).Offset = 0; 35 | ptMsg.Fields(1).Datatype = 7; 36 | ptMsg.Fields(1).Count = 1; 37 | ptMsg.Fields(2).Name = 'y'; 38 | ptMsg.Fields(2).Offset = 4; 39 | ptMsg.Fields(2).Datatype = 7; 40 | ptMsg.Fields(2).Count = 1; 41 | ptMsg.Fields(3).Name = 'z'; 42 | ptMsg.Fields(3).Offset = 8; 43 | ptMsg.Fields(3).Datatype = 7; 44 | ptMsg.Fields(3).Count = 1; 45 | ptMsg.Fields(4).Name = 'intensity'; 46 | ptMsg.Fields(4).Offset = 16; 47 | ptMsg.Fields(4).Datatype = 7; 48 | ptMsg.Fields(4).Count = 1; 49 | 50 | locs = reshape(filtered_ptCloud.Location,[],3); 51 | intensities = reshape(filtered_ptCloud.Intensity,[],1); 52 | data = [locs zeros(size(locs,1),1,'single') intensities zeros(size(locs,1),3,'single')]; 53 | dataPacked = reshape(permute(data,[2 1]),[],1); 54 | dataCasted = typecast(dataPacked,'uint8'); 55 | ptMsg.Data = dataCasted; 56 | end 57 | end -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/CANData.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint32 count 3 | uint32 id 4 | uint32 time 5 | uint16 flag 6 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/CANPacket.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint32 count 3 | uint32 id 4 | uint8 len 5 | uint8[8] dat 6 | uint16 flag 7 | uint32 time -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/CameraExtrinsic.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint32 xsize=4 3 | uint32 ysize=4 4 | float64[] calibration 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/CanInfo.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string tm 3 | int32 devmode 4 | int32 drvcontmode 5 | int32 drvoverridemode 6 | int32 drvservo 7 | int32 drivepedal 8 | int32 targetpedalstr 9 | int32 inputpedalstr 10 | float64 targetveloc 11 | float64 speed 12 | int32 driveshift 13 | int32 targetshift 14 | int32 inputshift 15 | int32 strmode 16 | int32 strcontmode 17 | int32 stroverridemode 18 | int32 strservo 19 | int32 targettorque 20 | int32 torque 21 | float64 angle 22 | float64 targetangle 23 | int32 bbrakepress 24 | int32 brakepedal 25 | int32 brtargetpedalstr 26 | int32 brinputpedalstr 27 | float64 battery 28 | int32 voltage 29 | float64 anp 30 | int32 battmaxtemparature 31 | int32 battmintemparature 32 | float64 maxchgcurrent 33 | float64 maxdischgcurrent 34 | float64 sideacc 35 | float64 accellfromp 36 | float64 anglefromp 37 | float64 brakepedalfromp 38 | float64 speedfr 39 | float64 speedfl 40 | float64 speedrr 41 | float64 speedrl 42 | float64 velocfromp2 43 | int32 drvmode 44 | int32 devpedalstrfromp 45 | int32 rpm 46 | float64 velocflfromp 47 | int32 ev_mode 48 | int32 temp 49 | int32 shiftfrmprius 50 | int32 light 51 | int32 gaslevel 52 | int32 door 53 | int32 cluise 54 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/CloudCluster.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | 3 | uint32 id 4 | string label 5 | float64 score 6 | 7 | sensor_msgs/PointCloud2 cloud 8 | 9 | geometry_msgs/PointStamped min_point 10 | geometry_msgs/PointStamped max_point 11 | geometry_msgs/PointStamped avg_point 12 | geometry_msgs/PointStamped centroid_point 13 | 14 | float64 estimated_angle 15 | 16 | geometry_msgs/Vector3 dimensions 17 | geometry_msgs/Vector3 eigen_values 18 | geometry_msgs/Vector3[] eigen_vectors 19 | 20 | #Array of 33 floats containing the FPFH descriptor 21 | std_msgs/Float32MultiArray fpfh_descriptor 22 | 23 | jsk_recognition_msgs/BoundingBox bounding_box 24 | geometry_msgs/PolygonStamped convex_hull 25 | 26 | # Indicator information 27 | # INDICATOR_LEFT 0 28 | # INDICATOR_RIGHT 1 29 | # INDICATOR_BOTH 2 30 | # INDICATOR_NONE 3 31 | uint32 indicator_state -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/CloudClusterArray.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | CloudCluster[] clusters -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ColorSet.msg: -------------------------------------------------------------------------------- 1 | ValueSet Hue 2 | ValueSet Sat 3 | ValueSet Val 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigApproximateNdtMapping.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 resolution 3 | float32 step_size 4 | float32 trans_epsilon 5 | int32 max_iterations 6 | float32 leaf_size 7 | float32 min_scan_range 8 | float32 max_scan_range 9 | float32 min_add_scan_shift 10 | float32 max_submap_size 11 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigCarDpm.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 score_threshold 3 | float32 group_threshold 4 | int32 Lambda 5 | int32 num_cells 6 | int32 num_bins -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigCarFusion.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 min_low_height 3 | float32 max_low_height 4 | float32 max_height 5 | int32 min_points 6 | float32 dispersion 7 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigCarKf.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 initial_lifespan 3 | int32 default_lifespan 4 | float32 noise_covariance 5 | float32 measurement_noise_covariance 6 | float32 error_estimate_covariance 7 | float32 percentage_of_overlapping 8 | int32 orb_features 9 | int32 use_orb -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigDecisionMaker.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | bool enable_force_state_change 3 | bool enable_display_marker 4 | float64 convergence_threshold 5 | uint32 convergence_count 6 | uint32 target_waypoint 7 | uint32 stopline_target_waypoint 8 | float64 stopline_target_ratio 9 | float64 shift_width 10 | 11 | float64 crawl_velocity 12 | float64 detection_area_rate 13 | 14 | string baselink_tf 15 | 16 | float64 detection_area_x1 17 | float64 detection_area_x2 18 | float64 detection_area_y1 19 | float64 detection_area_y2 -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigDistanceFilter.msg: -------------------------------------------------------------------------------- 1 | int32 sample_num 2 | float32 measurement_range 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigICP.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 init_pos_gnss 3 | float32 x 4 | float32 y 5 | float32 z 6 | float32 roll 7 | float32 pitch 8 | float32 yaw 9 | int32 use_predict_pose 10 | float32 error_threshold 11 | int32 maximum_iterations 12 | float32 transformation_epsilon 13 | float32 max_correspondence_distance 14 | float32 euclidean_fitness_epsilon 15 | float32 ransac_outlier_rejection_threshold 16 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigLaneRule.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 acceleration 3 | float32 stopline_search_radius 4 | int32 number_of_zeros_ahead 5 | int32 number_of_zeros_behind 6 | int32 number_of_smoothing_count 7 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigLaneSelect.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 distance_threshold_neighbor_lanes 3 | float32 lane_change_interval 4 | float32 lane_change_target_ratio 5 | float32 lane_change_target_minimum 6 | float32 vector_length_hermite_curve 7 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigLaneStop.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | bool manual_detection 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigLatticeVelocitySet.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 others_distance 3 | float32 detection_range 4 | int32 threshold_points 5 | float32 detection_height_top 6 | float32 detection_height_bottom 7 | float32 deceleration 8 | float32 velocity_change_limit 9 | float32 deceleration_range 10 | float32 temporal_waypoints_size 11 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigNdt.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 init_pos_gnss 3 | float32 x 4 | float32 y 5 | float32 z 6 | float32 roll 7 | float32 pitch 8 | float32 yaw 9 | #int32 lidar_original 10 | #int32 max 11 | #int32 min 12 | #int32 layer 13 | int32 use_predict_pose 14 | float32 error_threshold 15 | float32 resolution 16 | float32 step_size 17 | float32 trans_epsilon 18 | int32 max_iterations 19 | #float32 leaf_size 20 | #float32 angle_error 21 | #float32 shift_x 22 | #float32 shift_y 23 | #float32 shift_z 24 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigNdtMapping.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 resolution 3 | float32 step_size 4 | float32 trans_epsilon 5 | int32 max_iterations 6 | float32 leaf_size 7 | float32 min_scan_range 8 | float32 max_scan_range 9 | float32 min_add_scan_shift 10 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigNdtMappingOutput.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string filename 3 | float32 filter_res 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigPedestrianDpm.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 score_threshold 3 | float32 group_threshold 4 | int32 Lambda 5 | int32 num_cells 6 | int32 num_bins 7 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigPedestrianFusion.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 min_low_height 3 | float32 max_low_height 4 | float32 max_height 5 | int32 min_points 6 | float32 dispersion 7 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigPedestrianKf.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 initial_lifespan 3 | int32 default_lifespan 4 | float32 noise_covariance 5 | float32 measurement_noise_covariance 6 | float32 error_estimate_covariance 7 | float32 percentage_of_overlapping 8 | int32 orb_features 9 | int32 use_orb -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigPlannerSelector.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 latency_num 3 | int32 waypoints_num 4 | float32 convergence_num 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigPoints2Polygon.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 k_search 3 | float32 search_radius 4 | float32 mu 5 | int32 maximum_nearest_neighbors 6 | float32 maximum_surface_angle 7 | float32 minimum_angle 8 | float32 maximum_angle 9 | bool normal_consistency 10 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigRandomFilter.msg: -------------------------------------------------------------------------------- 1 | int32 sample_num 2 | float32 measurement_range 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigRayGroundFilter.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | 3 | float64 sensor_height 4 | float64 clipping_height 5 | float64 min_point_distance 6 | float64 radial_divider_angle 7 | float64 concentric_divider_distance 8 | float64 local_max_slope 9 | float64 general_max_slope 10 | float64 min_height_threshold 11 | float64 reclass_distance_threshold -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigRcnn.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 score_threshold #minimum score required to keep the detection [0.0, 1.0] (default 0.6) 3 | float32 group_threshold #minimum overlap percentage area required to supress detections(NMS threshold) [0.0, 1.0] (default 0.3) 4 | float32 slices_overlap #overlap percentage between image slices [0.0, 1.0] (default 0.7) 5 | float32 b_mean 6 | float32 g_mean 7 | float32 r_mean 8 | uint8 image_slices #number of times to slice the image and search (1, 100], larger value might improve detection but reduce performance (default 16) 9 | uint8 use_gpu 10 | uint8 gpu_device_id -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigRingFilter.msg: -------------------------------------------------------------------------------- 1 | int32 ring_div 2 | float32 voxel_leaf_size 3 | float32 measurement_range 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigRingGroundFilter.msg: -------------------------------------------------------------------------------- 1 | string sensor_model 2 | float32 sensor_height 3 | float32 max_slope 4 | float32 vertical_thres 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigSsd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 score_threshold #minimum score required to keep the detection [0.0, 1.0] (default 0.6) 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigTwistFilter.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 lateral_accel_limit 3 | float32 lowpass_gain_linear_x 4 | float32 lowpass_gain_angular_z 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigVelocitySet.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 stop_distance_obstacle 3 | float32 stop_distance_stopline 4 | float32 detection_range 5 | int32 threshold_points 6 | float32 detection_height_top 7 | float32 detection_height_bottom 8 | float32 deceleration_obstacle 9 | float32 deceleration_stopline 10 | float32 velocity_change_limit 11 | float32 deceleration_range 12 | float32 temporal_waypoints_size 13 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigVoxelGridFilter.msg: -------------------------------------------------------------------------------- 1 | float32 voxel_leaf_size 2 | float32 measurement_range 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigWaypointFollower.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 param_flag 3 | float32 velocity 4 | float32 lookahead_distance 5 | float32 lookahead_ratio 6 | float32 minimum_lookahead_distance 7 | float32 displacement_threshold 8 | float32 relative_angle_threshold 9 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ConfigWaypointLoader.msg: -------------------------------------------------------------------------------- 1 | string multi_lane_csv 2 | bool replanning_mode 3 | float32 velocity_max 4 | float32 velocity_min 5 | float32 accel_limit 6 | float32 decel_limit 7 | float32 radius_thresh 8 | float32 radius_min 9 | bool resample_mode 10 | float32 resample_interval 11 | int32 velocity_offset 12 | int32 end_point_offset 13 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ControlCommand.msg: -------------------------------------------------------------------------------- 1 | float64 linear_velocity 2 | float64 linear_acceleration #m/s^2 3 | float64 steering_angle 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ControlCommandStamped.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | ControlCommand cmd 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/DetectedObject.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | 3 | uint32 id 4 | string label 5 | float32 score #Score as defined by the detection, Optional 6 | std_msgs/ColorRGBA color # Define this object specific color 7 | 8 | ################ 3D BB 9 | string space_frame #3D Space coordinate frame of the object, required if pose and dimensions are defines 10 | geometry_msgs/Pose pose 11 | geometry_msgs/Vector3 dimensions 12 | geometry_msgs/Vector3 variance 13 | geometry_msgs/Twist velocity 14 | geometry_msgs/Twist acceleration 15 | 16 | sensor_msgs/PointCloud2 pointcloud 17 | 18 | geometry_msgs/PolygonStamped convex_hull 19 | autoware_msgs/LaneArray candidate_trajectories 20 | 21 | bool pose_reliable 22 | bool velocity_reliable 23 | bool acceleration_reliable 24 | 25 | ############### 2D Rect 26 | string image_frame # Image coordinate Frame, Required if x,y,w,h defined 27 | int32 x # X coord in image space(pixel) of the initial point of the Rect 28 | int32 y # Y coord in image space(pixel) of the initial point of the Rect 29 | int32 width # Width of the Rect in pixels 30 | int32 height # Height of the Rect in pixels 31 | float32 angle # Angle [0 to 2*PI), allow rotated rects 32 | 33 | sensor_msgs/Image roi_image 34 | 35 | ############### Indicator information 36 | uint8 indicator_state # INDICATOR_LEFT = 0, INDICATOR_RIGHT = 1, INDICATOR_BOTH = 2, INDICATOR_NONE = 3 37 | 38 | ############### Behavior State of the Detected Object 39 | uint8 behavior_state # FORWARD_STATE = 0, STOPPING_STATE = 1, BRANCH_LEFT_STATE = 2, BRANCH_RIGHT_STATE = 3, YIELDING_STATE = 4, ACCELERATING_STATE = 5, SLOWDOWN_STATE = 6 40 | 41 | # 42 | string[] user_defined_info -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/DetectedObjectArray.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | DetectedObject[] objects -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ExtractedPosition.msg: -------------------------------------------------------------------------------- 1 | # This message defines the information required to describe a lamp (bulb) 2 | # in a traffic signal, according to the information extracted from the ADAS Map 3 | # and the extrinsic camera calibration 4 | 5 | int32 signalId # Traffic Signal Lamp ID 6 | int32 u # Lamp ROI x in image coords 7 | int32 v # Lamp ROI y in image coords 8 | int32 radius # Lamp Radius 9 | float64 x # X position in map coordinates 10 | float64 y # Y position in map coordinates 11 | float64 z # Z position in map coordinates 12 | float64 hang # Azimuth "Horizontal Angle" 13 | int8 type # Lamp Type (red, yellow, green, ...) 14 | int32 linkId # Closest LinkID (lane) in VectorMap 15 | int32 plId # PoleID to which this Lamp belongs to 16 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ImageLaneObjects.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 lane_l_x1 # Left Lane 3 | int32 lane_l_y1 4 | int32 lane_l_x2 5 | int32 lane_l_y2 6 | int32 lane_r_x1 # Right Lane 7 | int32 lane_r_y1 8 | int32 lane_r_x2 9 | int32 lane_r_y2 10 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ImageObjects.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint8 car_num 3 | int32[] car_type 4 | float32[] score 5 | int32[] corner_point 6 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/LaneArray.msg: -------------------------------------------------------------------------------- 1 | lane[] lanes -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/PointsImage.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32[] distance 3 | float32[] intensity 4 | float32[] min_height 5 | float32[] max_height 6 | int32 max_y 7 | int32 min_y 8 | int32 image_height 9 | int32 image_width -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/RemoteCmd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | autoware_msgs/VehicleCmd vehicle_cmd 3 | int32 control_mode 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ScanImage.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32[] distance 3 | float32[] intensity 4 | int32 max_y 5 | int32 min_y -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/Signals.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | ExtractedPosition[] Signals 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/Sync_time_diff.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 time_diff 3 | time camera 4 | time lidar -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/Sync_time_monitor.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 image_raw 3 | float64 points_raw 4 | float64 points_image 5 | float64 vscan_points 6 | float64 vscan_image 7 | float64 image_obj 8 | float64 image_obj_ranged 9 | float64 image_obj_tracked 10 | float64 current_pose 11 | float64 obj_label 12 | float64 cluster_centroids 13 | float64 obj_pose 14 | float64 execution_time 15 | float64 cycle_time 16 | float64 time_diff 17 | 18 | 19 | # time image_raw 20 | # time points_raw 21 | # time image_obj 22 | # time image_obj_ranged 23 | # time image_obj_tracked 24 | # time current_pose 25 | # time obj_label 26 | # time cluster_centroids 27 | # time obj_pose -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/TrafficLightResult.msg: -------------------------------------------------------------------------------- 1 | # This message defines meta information for a traffic light status 2 | Header header 3 | 4 | # Each bulb is assigned with an Id 5 | # The TLR node convention is to use the yellow bulb's ID 6 | int32 light_id 7 | 8 | # The result as provided by the tlr nodes 9 | # Red and Yellow states are both treated as STOP 10 | # RED = 0 11 | # YELLOW = 0 12 | # GREEN = 1 13 | # UNKNOWN = 2 14 | int32 recognition_result 15 | 16 | # This string is used by the Audio Player 17 | string recognition_result_str 18 | 19 | # LaneId to which this traffic light result belongs to 20 | # this Id is defined by the ADAS MAP 21 | int32 lane_id 22 | 23 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/TrafficLightResultArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | TrafficLightResult[] results 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/TunedResult.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | ColorSet Red 3 | ColorSet Yellow 4 | ColorSet Green 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ValueSet.msg: -------------------------------------------------------------------------------- 1 | int32 center 2 | int32 range 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/VehicleCmd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | autoware_msgs/steer_cmd steer_cmd 3 | autoware_msgs/accel_cmd accel_cmd 4 | autoware_msgs/brake_cmd brake_cmd 5 | autoware_msgs/lamp_cmd lamp_cmd 6 | int32 gear 7 | int32 mode 8 | geometry_msgs/TwistStamped twist_cmd 9 | autoware_msgs/ControlCommand ctrl_cmd 10 | int32 emergency 11 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/VehicleStatus.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string tm 3 | 4 | # Powertrain 5 | int32 drivemode 6 | int32 steeringmode 7 | int32 MODE_MANUAL=0 8 | int32 MODE_AUTO=1 9 | 10 | int32 gearshift 11 | 12 | float64 speed 13 | int32 drivepedal 14 | int32 brakepedal 15 | 16 | float64 angle 17 | 18 | # Body 19 | int32 lamp 20 | int32 LAMP_LEFT=1 21 | int32 LAMP_RIGHT=2 22 | int32 LAMP_HAZARD=3 23 | 24 | int32 light 25 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/WaypointState.msg: -------------------------------------------------------------------------------- 1 | int32 aid 2 | uint8 NULLSTATE=0 3 | uint8 lanechange_state 4 | 5 | uint8 steering_state 6 | uint8 STR_LEFT=1 7 | uint8 STR_RIGHT=2 8 | uint8 STR_STRAIGHT=3 9 | 10 | uint8 accel_state 11 | uint8 stopline_state 12 | uint8 TYPE_NULL=0 13 | uint8 TYPE_STOPLINE=1 14 | uint8 TYPE_STOP=2 15 | # 1 is stopline, 2 is stop which 2 can only be released manually. 16 | uint64 event_state 17 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/accel_cmd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 accel 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/adjust_xy.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 x 3 | int32 y 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/brake_cmd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 brake 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/centroids.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | geometry_msgs/Point[] points 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/dtlane.msg: -------------------------------------------------------------------------------- 1 | float64 dist 2 | float64 dir 3 | float64 apara 4 | float64 r 5 | float64 slope 6 | float64 cant 7 | float64 lw 8 | float64 rw 9 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/geometric_rectangle.msg: -------------------------------------------------------------------------------- 1 | float32 wl 2 | float32 wr 3 | float32 lf 4 | float32 lb -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/icp_stat.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 exe_time 3 | #int32 iteration 4 | float32 score 5 | float32 velocity 6 | float32 acceleration 7 | int32 use_predict_pose 8 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/image_obj.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string type 3 | image_rect[] obj 4 | # XXX Should this message have 'score' ? 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/image_obj_ranged.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string type 3 | image_rect_ranged[] obj 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/image_obj_tracked.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string type 3 | uint8 total_num 4 | int32[] obj_id 5 | image_rect_ranged[] rect_ranged 6 | int32[] real_data 7 | int32[] lifespan -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/image_rect.msg: -------------------------------------------------------------------------------- 1 | int32 x 2 | int32 y 3 | int32 height 4 | int32 width 5 | float32 score 6 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/image_rect_ranged.msg: -------------------------------------------------------------------------------- 1 | image_rect rect 2 | float32 range 3 | float32 min_height 4 | float32 max_height 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/indicator_cmd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 l 3 | int32 r 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/lamp_cmd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 l 3 | int32 r 4 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/lane.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 increment 3 | int32 lane_id 4 | waypoint[] waypoints 5 | 6 | uint32 lane_index 7 | float32 cost 8 | float32 closest_object_distance 9 | float32 closest_object_velocity 10 | bool is_blocked 11 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/ndt_stat.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 exe_time 3 | int32 iteration 4 | float32 score 5 | float32 velocity 6 | float32 acceleration 7 | int32 use_predict_pose 8 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/obj_label.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string type 3 | int32[] obj_id 4 | geometry_msgs/Point[] reprojected_pos 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/obj_pose.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string type 3 | int32[] obj_id 4 | geometry_msgs/PoseArray[] obj 5 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/projection_matrix.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64[16] projection_matrix -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/state.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string main_state 3 | string acc_state 4 | string str_state 5 | string behavior_state 6 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/state_cmd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 cmd 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/steer_cmd.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 steer 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/traffic_light.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 traffic_light 3 | -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/vscan_tracked.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/Point position 2 | float32 orientation 3 | float32 velocity 4 | geometric_rectangle geo_rect -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/vscan_tracked_array.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | vscan_tracked[] obj_tracked -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/msg/waypoint.msg: -------------------------------------------------------------------------------- 1 | # global id 2 | int32 gid 3 | # local id 4 | int32 lid 5 | geometry_msgs/PoseStamped pose 6 | geometry_msgs/TwistStamped twist 7 | dtlane dtlane 8 | int32 change_flag 9 | WaypointState wpstate 10 | 11 | uint32 lane_id 12 | uint32 left_lane_id 13 | uint32 right_lane_id 14 | uint32 stop_line_id 15 | float32 cost 16 | float32 time_cost 17 | 18 | # Lane Direction 19 | # FORWARD = 0 20 | # FORWARD_LEFT = 1 21 | # FORWARD_RIGHT = 2 22 | # BACKWARD = 3 23 | # BACKWARD_LEFT = 4 24 | # BACKWARD_RIGHT = 5 25 | # STANDSTILL = 6 26 | uint32 direction -------------------------------------------------------------------------------- /custom_msgs/autoware_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | autoware_msgs 4 | 1.8.0 5 | The autoware_msgs package 6 | Yusuke Fujii 7 | BSD 8 | catkin 9 | message_generation 10 | std_msgs 11 | geometry_msgs 12 | sensor_msgs 13 | jsk_recognition_msgs 14 | message_runtime 15 | std_msgs 16 | geometry_msgs 17 | sensor_msgs 18 | jsk_recognition_msgs 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package dbw_mkz_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.8.0 (2018-08-31) 6 | ------------------ 7 | 8 | 1.7.0 (2018-05-18) 9 | ------------------ 10 | * update Version from 1.6.3 to 1.7.0 in package.xml and CHANGELOG.rst 11 | * Contributors: Kosuke Murakami 12 | 13 | 1.6.3 (2018-03-06) 14 | ------------------ 15 | 16 | 1.6.2 (2018-02-27) 17 | ------------------ 18 | * Update CHANGELOG 19 | * Contributors: Yusuke FUJII 20 | 21 | 1.6.1 (2018-01-20) 22 | ------------------ 23 | * update CHANGELOG 24 | * Contributors: Yusuke FUJII 25 | 26 | 1.6.0 (2017-12-11) 27 | ------------------ 28 | * Prepare release for 1.6.0 29 | * adapted the version to the current version 30 | * Add pacmod interface 31 | * Contributors: TomohitoAndo, Yamato ANDO 32 | 33 | 1.5.1 (2017-09-25) 34 | ------------------ 35 | 36 | 1.5.0 (2017-09-21) 37 | ------------------ 38 | 39 | 1.4.0 (2017-08-04) 40 | ------------------ 41 | 42 | 1.3.1 (2017-07-16) 43 | ------------------ 44 | 45 | 1.3.0 (2017-07-14) 46 | ------------------ 47 | 48 | 1.2.0 (2017-06-07) 49 | ------------------ 50 | 51 | 1.1.2 (2017-02-27 23:10) 52 | ------------------------ 53 | 54 | 1.1.1 (2017-02-27 22:25) 55 | ------------------------ 56 | 57 | 1.1.0 (2017-02-24) 58 | ------------------ 59 | 60 | 1.0.1 (2017-01-14) 61 | ------------------ 62 | 63 | 1.0.0 (2016-12-22) 64 | ------------------ 65 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(dbw_mkz_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | message_generation 6 | std_msgs 7 | geometry_msgs 8 | ) 9 | 10 | add_message_files(DIRECTORY msg FILES 11 | AmbientLight.msg 12 | BrakeCmd.msg 13 | BrakeInfoReport.msg 14 | BrakeReport.msg 15 | FuelLevelReport.msg 16 | Gear.msg 17 | GearCmd.msg 18 | GearReject.msg 19 | GearReport.msg 20 | HillStartAssist.msg 21 | Misc1Report.msg 22 | ParkingBrake.msg 23 | SteeringCmd.msg 24 | SteeringReport.msg 25 | SurroundReport.msg 26 | ThrottleCmd.msg 27 | ThrottleInfoReport.msg 28 | ThrottleReport.msg 29 | TirePressureReport.msg 30 | TurnSignal.msg 31 | TurnSignalCmd.msg 32 | TwistCmd.msg 33 | WatchdogCounter.msg 34 | WheelPositionReport.msg 35 | WheelSpeedReport.msg 36 | Wiper.msg 37 | ) 38 | 39 | generate_messages(DEPENDENCIES 40 | std_msgs 41 | geometry_msgs 42 | ) 43 | 44 | catkin_package(CATKIN_DEPENDS 45 | message_runtime 46 | std_msgs 47 | geometry_msgs 48 | ) 49 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/AmbientLight.msg: -------------------------------------------------------------------------------- 1 | uint8 status 2 | 3 | uint8 DARK=0 4 | uint8 LIGHT=1 5 | uint8 TWILIGHT=2 6 | uint8 TUNNEL_ON=3 7 | uint8 TUNNEL_OFF=4 8 | uint8 NO_DATA=7 9 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/BrakeCmd.msg: -------------------------------------------------------------------------------- 1 | # Brake pedal 2 | # Options defined below 3 | float32 pedal_cmd 4 | uint8 pedal_cmd_type 5 | 6 | # Brake On Off (BOO), brake lights 7 | bool boo_cmd 8 | 9 | # Enable 10 | bool enable 11 | 12 | # Clear driver overrides 13 | bool clear 14 | 15 | # Ignore driver overrides 16 | bool ignore 17 | 18 | # Watchdog counter (optional) 19 | uint8 count 20 | 21 | uint8 CMD_NONE=0 22 | uint8 CMD_PEDAL=1 # Unitless, range 0.15 to 0.50 23 | uint8 CMD_PERCENT=2 # Percent of maximum torque, range 0 to 1 24 | uint8 CMD_TORQUE=3 # Nm, range 0 to 3250 25 | 26 | float32 TORQUE_BOO=520 # Nm, brake lights threshold 27 | float32 TORQUE_MAX=3412 # Nm, maximum torque 28 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/BrakeInfoReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Wheel torques (Nm) 4 | float32 brake_torque_request 5 | float32 brake_torque_actual 6 | float32 wheel_torque_actual 7 | 8 | # Vehicle Acceleration (m/s^2) 9 | float32 accel_over_ground 10 | 11 | # Hill Start Assist 12 | HillStartAssist hsa 13 | 14 | # Anti-lock Brakes 15 | bool abs_active 16 | bool abs_enabled 17 | 18 | # Stability Control 19 | bool stab_active 20 | bool stab_enabled 21 | 22 | # Traction Control 23 | bool trac_active 24 | bool trac_enabled 25 | 26 | # Parking Brake 27 | ParkingBrake parking_brake 28 | 29 | # Misc 30 | bool stationary 31 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/BrakeReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Brake pedal 4 | # Unitless, range 0.15 to 0.50 5 | float32 pedal_input 6 | float32 pedal_cmd 7 | float32 pedal_output 8 | 9 | # Braking torque (Nm) 10 | float32 torque_input 11 | float32 torque_cmd 12 | float32 torque_output 13 | 14 | # Brake On Off (BOO), brake lights 15 | bool boo_input 16 | bool boo_cmd 17 | bool boo_output 18 | 19 | # Status 20 | bool enabled # Enabled 21 | bool override # Driver override 22 | bool driver # Driver activity 23 | bool timeout # Command timeout 24 | 25 | # Watchdog Counter 26 | WatchdogCounter watchdog_counter 27 | bool watchdog_braking 28 | bool fault_wdc 29 | 30 | # Faults 31 | bool fault_ch1 32 | bool fault_ch2 33 | bool fault_boo 34 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/FuelLevelReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Fuel level (%, 0 to 100) 4 | float32 fuel_level 5 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/Gear.msg: -------------------------------------------------------------------------------- 1 | uint8 gear 2 | 3 | uint8 NONE=0 4 | uint8 PARK=1 5 | uint8 REVERSE=2 6 | uint8 NEUTRAL=3 7 | uint8 DRIVE=4 8 | uint8 LOW=5 9 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/GearCmd.msg: -------------------------------------------------------------------------------- 1 | # Gear command enumeration 2 | Gear cmd 3 | 4 | # Clear driver overrides 5 | bool clear 6 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/GearReject.msg: -------------------------------------------------------------------------------- 1 | uint8 value 2 | 3 | uint8 NONE=0 # Not rejected 4 | uint8 SHIFT_IN_PROGRESS=1 # Shift in progress 5 | uint8 OVERRIDE=2 # Override on brake, throttle, or steering 6 | uint8 ROTARY_LOW=3 # Rotary shifter can't shift to Low 7 | uint8 ROTARY_PARK=4 # Rotary shifter can't shift out of Park 8 | uint8 VEHICLE=5 # Rejected by vehicle (try pressing the brakes) 9 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/GearReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Current gear enumeration 4 | Gear state 5 | 6 | # Gear command enumeration 7 | Gear cmd 8 | 9 | # Gear reject enumeration 10 | GearReject reject 11 | 12 | # Status 13 | bool override 14 | 15 | # Faults 16 | bool fault_bus 17 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/HillStartAssist.msg: -------------------------------------------------------------------------------- 1 | uint8 status 2 | uint8 mode 3 | 4 | uint8 STAT_INACTIVE=0 5 | uint8 STAT_FINDING_GRADIENT=1 6 | uint8 STAT_ACTIVE_PRESSED=2 7 | uint8 STAT_ACTIVE_RELEASED=3 8 | uint8 STAT_FAST_RELEASE=4 9 | uint8 STAT_SLOW_RELEASE=5 10 | uint8 STAT_FAILED=6 11 | uint8 STAT_UNDEFINED=7 12 | 13 | uint8 MODE_OFF=0 14 | uint8 MODE_AUTO=1 15 | uint8 MODE_MANUAL=2 16 | uint8 MODE_UNDEFINED=3 17 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/Misc1Report.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Turn Signal enumeration 4 | TurnSignal turn_signal 5 | 6 | # High beams 7 | bool high_beam_headlights 8 | 9 | # Front Windshield Wipers enumeration 10 | Wiper wiper 11 | 12 | # Ambient Light Sensor enumeration 13 | AmbientLight ambient_light 14 | 15 | # Buttons 16 | bool btn_cc_on # Cruise Control On 17 | bool btn_cc_off # Cruise Control Off 18 | bool btn_cc_on_off # Cruise Control On/Off Toggle 19 | bool btn_cc_res # Cruise Control Resume 20 | bool btn_cc_cncl # Cruise Control Cancel 21 | bool btn_cc_res_cncl # Cruise Control Resume/Cancel 22 | bool btn_cc_set_inc # Cruise Control Set+ 23 | bool btn_cc_set_dec # Cruise Control Set- 24 | bool btn_cc_gap_inc # Cruise Control Gap+ 25 | bool btn_cc_gap_dec # Cruise Control Gap- 26 | bool btn_la_on_off # Lane Assist On/Off Toggle 27 | bool btn_ld_ok # Left D-Pad OK 28 | bool btn_ld_up # Left D-Pad Up 29 | bool btn_ld_down # Left D-Pad Down 30 | bool btn_ld_left # Left D-Pad Left 31 | bool btn_ld_right # Left D-Pad Right 32 | 33 | # Faults 34 | bool fault_bus 35 | 36 | # Doors 37 | bool door_driver 38 | bool door_passenger 39 | bool door_rear_left 40 | bool door_rear_right 41 | bool door_hood 42 | bool door_trunk 43 | 44 | # Passenger seat 45 | bool passenger_detect 46 | bool passenger_airbag 47 | 48 | # Seat Belts 49 | bool buckle_driver 50 | bool buckle_passenger 51 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/ParkingBrake.msg: -------------------------------------------------------------------------------- 1 | uint8 status 2 | 3 | uint8 OFF=0 4 | uint8 TRANS=1 5 | uint8 ON=2 6 | uint8 FAULT=3 7 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/SteeringCmd.msg: -------------------------------------------------------------------------------- 1 | # Steering Wheel 2 | float32 steering_wheel_angle_cmd # rad, range -8.2 to 8.2 3 | float32 steering_wheel_angle_velocity # rad/s, range 0 to 8.7, 0 = maximum 4 | 5 | # Enable 6 | bool enable 7 | 8 | # Clear driver overrides 9 | bool clear 10 | 11 | # Ignore driver overrides 12 | bool ignore 13 | 14 | # Disable the driver override audible warning 15 | bool quiet 16 | 17 | # Watchdog counter (optional) 18 | uint8 count 19 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/SteeringReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Steering Wheel 4 | float32 steering_wheel_angle # rad 5 | float32 steering_wheel_angle_cmd # rad 6 | float32 steering_wheel_torque # Nm 7 | 8 | # Vehicle Speed 9 | float32 speed # m/s 10 | 11 | # Status 12 | bool enabled # Enabled 13 | bool override # Driver override 14 | bool timeout # Command timeout 15 | 16 | # Watchdog Counter 17 | bool fault_wdc 18 | 19 | # Faults 20 | bool fault_bus1 21 | bool fault_bus2 22 | bool fault_calibration 23 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/SurroundReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Cross Traffic Alert (CTA) 4 | bool cta_left_alert 5 | bool cta_right_alert 6 | bool cta_left_enabled 7 | bool cta_right_enabled 8 | 9 | # Blind Spot Information System (BLIS) 10 | bool blis_left_alert 11 | bool blis_right_alert 12 | bool blis_left_enabled 13 | bool blis_right_enabled 14 | 15 | # Sonar Sensors 16 | bool sonar_enabled 17 | bool sonar_fault 18 | 19 | # Sonar ranges in meters, zero is no-detection 20 | float32[12] sonar 21 | 22 | # Sonar index enumeration 23 | uint8 FRONT_LEFT_SIDE=0 24 | uint8 FRONT_LEFT_CORNER=1 25 | uint8 FRONT_LEFT_CENTER=2 26 | uint8 FRONT_RIGHT_CENTER=3 27 | uint8 FRONT_RIGHT_CORNER=4 28 | uint8 FRONT_RIGHT_SIDE=5 29 | uint8 REAR_LEFT_SIDE=6 30 | uint8 REAR_LEFT_CORNER=7 31 | uint8 REAR_LEFT_CENTER=8 32 | uint8 REAR_RIGHT_CENTER=9 33 | uint8 REAR_RIGHT_CORNER=10 34 | uint8 REAR_RIGHT_SIDE=11 35 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/ThrottleCmd.msg: -------------------------------------------------------------------------------- 1 | # Throttle pedal 2 | # Options defined below 3 | float32 pedal_cmd 4 | uint8 pedal_cmd_type 5 | 6 | # Enable 7 | bool enable 8 | 9 | # Clear driver overrides 10 | bool clear 11 | 12 | # Ignore driver overrides 13 | bool ignore 14 | 15 | # Watchdog counter (optional) 16 | uint8 count 17 | 18 | uint8 CMD_NONE=0 19 | uint8 CMD_PEDAL=1 # Unitless, range 0.15 to 0.80 20 | uint8 CMD_PERCENT=2 # Percent of maximum throttle, range 0 to 1 21 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/ThrottleInfoReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Throttle Pedal 4 | float32 throttle_pc # Throttle pedal percent, range 0 to 1 5 | float32 throttle_rate # Throttle pedal change per second (1/s) 6 | 7 | # Engine 8 | float32 engine_rpm # Engine Speed (rpm) 9 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/ThrottleReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Throttle pedal 4 | # Unitless, range 0.15 to 0.50 5 | float32 pedal_input 6 | float32 pedal_cmd 7 | float32 pedal_output 8 | 9 | # Status 10 | bool enabled # Enabled 11 | bool override # Driver override 12 | bool driver # Driver activity 13 | bool timeout # Command timeout 14 | 15 | # Watchdog Counter 16 | WatchdogCounter watchdog_counter 17 | bool fault_wdc 18 | 19 | # Faults 20 | bool fault_ch1 21 | bool fault_ch2 22 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/TirePressureReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Tire pressures (kPa) 4 | float32 front_left 5 | float32 front_right 6 | float32 rear_left 7 | float32 rear_right 8 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/TurnSignal.msg: -------------------------------------------------------------------------------- 1 | uint8 value 2 | 3 | uint8 NONE=0 4 | uint8 LEFT=1 5 | uint8 RIGHT=2 6 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/TurnSignalCmd.msg: -------------------------------------------------------------------------------- 1 | # Turn signal command enumeration 2 | TurnSignal cmd 3 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/TwistCmd.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/Twist twist 2 | float32 accel_limit # m/s^2, zero = no limit 3 | float32 decel_limit # m/s^2, zero = no limit 4 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/WatchdogCounter.msg: -------------------------------------------------------------------------------- 1 | uint8 source 2 | 3 | uint8 NONE=0 # No source for watchdog counter fault 4 | uint8 OTHER_BRAKE=1 # Fault determined by brake controller 5 | uint8 OTHER_THROTTLE=2 # Fault determined by throttle controller 6 | uint8 OTHER_STEERING=3 # Fault determined by steering controller 7 | uint8 BRAKE_COUNTER=4 # Brake command counter failed to increment 8 | uint8 BRAKE_DISABLED=5 # Brake transition to disabled while in gear or moving 9 | uint8 BRAKE_COMMAND=6 # Brake command timeout after 100ms 10 | uint8 BRAKE_REPORT=7 # Brake report timeout after 100ms 11 | uint8 THROTTLE_COUNTER=8 # Throttle command counter failed to increment 12 | uint8 THROTTLE_DISABLED=9 # Throttle transition to disabled while in gear or moving 13 | uint8 THROTTLE_COMMAND=10 # Throttle command timeout after 100ms 14 | uint8 THROTTLE_REPORT=11 # Throttle report timeout after 100ms 15 | uint8 STEERING_COUNTER=12 # Steering command counter failed to increment 16 | uint8 STEERING_DISABLED=13 # Steering transition to disabled while in gear or moving 17 | uint8 STEERING_COMMAND=14 # Steering command timeout after 100ms 18 | uint8 STEERING_REPORT=15 # Steering report timeout after 100ms 19 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/WheelPositionReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Wheel positions (counts) 4 | int16 front_left 5 | int16 front_right 6 | int16 rear_left 7 | int16 rear_right 8 | 9 | # Conversion factor 10 | float32 COUNTS_PER_REV=125.5 11 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/WheelSpeedReport.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Wheel speeds (rad/s) 4 | float32 front_left 5 | float32 front_right 6 | float32 rear_left 7 | float32 rear_right 8 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/msg/Wiper.msg: -------------------------------------------------------------------------------- 1 | uint8 status 2 | 3 | uint8 OFF=0 4 | uint8 AUTO_OFF=1 5 | uint8 OFF_MOVING=2 6 | uint8 MANUAL_OFF=3 7 | uint8 MANUAL_ON=4 8 | uint8 MANUAL_LOW=5 9 | uint8 MANUAL_HIGH=6 10 | uint8 MIST_FLICK=7 11 | uint8 WASH=8 12 | uint8 AUTO_LOW=9 13 | uint8 AUTO_HIGH=10 14 | uint8 COURTESYWIPE=11 15 | uint8 AUTO_ADJUST=12 16 | uint8 RESERVED=13 17 | uint8 STALLED=14 18 | uint8 NO_DATA=15 19 | -------------------------------------------------------------------------------- /custom_msgs/dbw_mkz_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | dbw_mkz_msgs 4 | 1.8.0 5 | 6 | Drive-by-wire messages for the Lincoln MKZ 7 | 8 | 9 | BSD 10 | Kevin Hallenbeck 11 | Kevin Hallenbeck 12 | http://dataspeedinc.com 13 | https://bitbucket.org/dataspeedinc/dbw_mkz_ros 14 | https://bitbucket.org/dataspeedinc/dbw_mkz_ros/issues 15 | 16 | catkin 17 | 18 | std_msgs 19 | geometry_msgs 20 | message_generation 21 | 22 | std_msgs 23 | geometry_msgs 24 | message_runtime 25 | 26 | 27 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Accuracy.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 accuracy 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/BoolStamped.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | bool data 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/BoundingBox.msg: -------------------------------------------------------------------------------- 1 | # BoundingBox represents a oriented bounding box. 2 | Header header 3 | geometry_msgs/Pose pose 4 | geometry_msgs/Vector3 dimensions # size of bounding box (x, y, z) 5 | # You can use this field to hold value such as likelihood 6 | float32 value 7 | uint32 label 8 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/BoundingBoxArray.msg: -------------------------------------------------------------------------------- 1 | # BoundingBoxArray is a list of BoundingBox. 2 | # You can use jsk_rviz_plugins to visualize BoungingBoxArray on rviz. 3 | Header header 4 | BoundingBox[] boxes 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/BoundingBoxArrayWithCameraInfo.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | BoundingBoxArray boxes 3 | sensor_msgs/CameraInfo camera_info 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/BoundingBoxMovement.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | BoundingBox box 3 | geometry_msgs/Pose handle_pose 4 | geometry_msgs/PoseStamped destination 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Circle2D.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 radius 3 | float64 x 4 | float64 y 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Circle2DArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Circle2D[] circles 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ClassificationResult.msg: -------------------------------------------------------------------------------- 1 | # information about frame and timestamp 2 | Header header 3 | 4 | # prediction results 5 | uint32[] labels # numerical labels 6 | string[] label_names # non-numerical labels 7 | float64[] label_proba # probabilities of labels 8 | float64[] probabilities # probabilities about each classification for all target_names 9 | 10 | # information about classifier 11 | string classifier # name of classifier 12 | string[] target_names # set in which label_names should be 13 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ClusterPointIndices.msg: -------------------------------------------------------------------------------- 1 | # ClusterPointIndices is used to represent segmentation result. 2 | # Simply put, ClusterPointIndices is a list of PointIndices. 3 | Header header 4 | pcl_msgs/PointIndices[] cluster_indices 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ColorHistogram.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32[] histogram 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ColorHistogramArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | ColorHistogram[] histograms 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ContactSensor.msg: -------------------------------------------------------------------------------- 1 | # Header 2 | Header header 3 | 4 | # Whether sensor detects contact or not 5 | bool contact 6 | 7 | string link_name 8 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ContactSensorArray.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | jsk_recognition_msgs/ContactSensor[] datas -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/DepthCalibrationParameter.msg: -------------------------------------------------------------------------------- 1 | # each vector stands for C(u, v) 2 | # C(u, v) = a_0 * u^2 + a_1 * u + a_2 * v^2 + a_3 * v + a_4 3 | float64[] coefficients2 4 | float64[] coefficients1 5 | float64[] coefficients0 6 | bool use_abs 7 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/DepthErrorResult.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint32 u 3 | uint32 v 4 | float32 center_u 5 | float32 center_v 6 | float32 true_depth 7 | float32 observed_depth 8 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/HeightmapConfig.msg: -------------------------------------------------------------------------------- 1 | float32 min_x 2 | float32 max_x 3 | float32 min_y 4 | float32 max_y 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Histogram.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64[] histogram 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/HistogramWithRange.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | HistogramWithRangeBin[] bins 3 | 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/HistogramWithRangeArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | HistogramWithRange[] histograms 3 | 4 | 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/HistogramWithRangeBin.msg: -------------------------------------------------------------------------------- 1 | float64 min_value 2 | float64 max_value 3 | uint32 count 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ICPResult.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | geometry_msgs/Pose pose 3 | string name 4 | float64 score -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ImageDifferenceValue.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | float32 difference 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Int32Stamped.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 data 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Label.msg: -------------------------------------------------------------------------------- 1 | int32 id 2 | string name 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/LabelArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Label[] labels 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Line.msg: -------------------------------------------------------------------------------- 1 | float64 x1 2 | float64 y1 3 | float64 x2 4 | float64 y2 5 | 6 | 7 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/LineArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Line[] lines 3 | 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ModelCoefficientsArray.msg: -------------------------------------------------------------------------------- 1 | # ModelCoefficientsArray is used to represent coefficients of model 2 | # for each segmented clusters. 3 | # Simply put, ModelCoefficientsArray is a list of ModelCoefficients. 4 | Header header 5 | pcl_msgs/ModelCoefficients[] coefficients 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Object.msg: -------------------------------------------------------------------------------- 1 | # object instant info (ex. oreo_cookie) 2 | int32 id # object id 3 | string name # object name 4 | 5 | # object class info (ex. snack) 6 | int32 class_id 7 | string class_name 8 | 9 | string[] image_resources # image urls 10 | string mesh_resource # mesh file url 11 | 12 | float32 weight # weight [kg] 13 | geometry_msgs/Vector3 dimensions # bounding box [m] 14 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ObjectArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | jsk_recognition_msgs/Object[] objects 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ParallelEdge.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | pcl_msgs/PointIndices[] cluster_indices 3 | pcl_msgs/ModelCoefficients[] coefficients 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/ParallelEdgeArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | ParallelEdge[] edge_groups 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/PeoplePose.msg: -------------------------------------------------------------------------------- 1 | string[] limb_names 2 | geometry_msgs/Pose[] poses 3 | float32[] scores -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/PeoplePoseArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | jsk_recognition_msgs/PeoplePose[] poses 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/PlotData.msg: -------------------------------------------------------------------------------- 1 | uint32 SCATTER=1 2 | uint32 LINE=2 3 | 4 | Header header 5 | float32[] xs 6 | float32[] ys 7 | uint32 type #SCATTER or LINE 8 | string label 9 | bool fit_line 10 | bool fit_line_ransac 11 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/PlotDataArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | jsk_recognition_msgs/PlotData[] data 3 | bool no_legend 4 | float32 legend_font_size 5 | float32 max_x 6 | float32 min_x 7 | float32 min_y 8 | float32 max_y 9 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/PointsArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | sensor_msgs/PointCloud2[] cloud_list 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/PolygonArray.msg: -------------------------------------------------------------------------------- 1 | # PolygonArray is a list of PolygonStamped. 2 | # You can use jsk_rviz_plugins to visualize PolygonArray on rviz. 3 | Header header 4 | geometry_msgs/PolygonStamped[] polygons 5 | uint32[] labels 6 | float32[] likelihood 7 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/PosedCameraInfo.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | sensor_msgs/CameraInfo camera_info 3 | geometry_msgs/Pose offset 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Rect.msg: -------------------------------------------------------------------------------- 1 | int32 x 2 | int32 y 3 | int32 width 4 | int32 height 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/RectArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Rect[] rects 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/RotatedRect.msg: -------------------------------------------------------------------------------- 1 | float64 x 2 | float64 y 3 | float64 width 4 | float64 height 5 | float64 angle # degree 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/RotatedRectStamped.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | RotatedRect rect 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Segment.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/Point start_point 2 | geometry_msgs/Point end_point 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SegmentArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Segment[] segments 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SegmentStamped.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Segment segment 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SimpleHandle.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | geometry_msgs/Pose pose 3 | float64 handle_width 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SimpleOccupancyGrid.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | # plane coefficients 3 | float32[4] coefficients 4 | # cells 5 | float32 resolution 6 | geometry_msgs/Point[] cells 7 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SimpleOccupancyGridArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | SimpleOccupancyGrid[] grids 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SlicedPointCloud.msg: -------------------------------------------------------------------------------- 1 | sensor_msgs/PointCloud2 point_cloud 2 | uint8 slice_index 3 | uint8 sequence_id 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SnapItRequest.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint8 MODEL_PLANE=0 3 | uint8 MODEL_CYLINDER=1 4 | uint8 model_type 5 | 6 | geometry_msgs/PolygonStamped target_plane 7 | 8 | geometry_msgs/PointStamped center 9 | geometry_msgs/Vector3Stamped direction 10 | float64 radius 11 | float64 height 12 | # parameters, 0 means 13 | float64 max_distance 14 | float64 eps_angle 15 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SparseImage.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | uint32 width 4 | uint32 height 5 | 6 | # each uint8 or uint16 contains position of white pixel expressed like: "(x << 8 or 16) ^ y" 7 | # if max(width, height) > 256(=2^8) use data32 array, else use data16 array. 8 | uint16[] data16 9 | uint32[] data32 10 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SparseOccupancyGrid.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | geometry_msgs/Pose origin_pose 3 | float32 resolution 4 | 5 | SparseOccupancyGridColumn[] columns 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SparseOccupancyGridArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | SparseOccupancyGrid[] grids 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SparseOccupancyGridCell.msg: -------------------------------------------------------------------------------- 1 | int32 row_index 2 | float32 value 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/SparseOccupancyGridColumn.msg: -------------------------------------------------------------------------------- 1 | int32 column_index 2 | SparseOccupancyGridCell[] cells 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/TimeRange.msg: -------------------------------------------------------------------------------- 1 | # Represents range of time. 2 | std_msgs/Header header 3 | time start 4 | time end 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/Torus.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | bool failure 3 | geometry_msgs/Pose pose 4 | float64 large_radius 5 | float64 small_radius 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/TorusArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Torus[] toruses 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/TrackerStatus.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | # if true, it means the tracker is trying to track object, 3 | # else, the tracker think scene is stable and no need to track 4 | # to save computational resource. 5 | bool is_tracking 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/TrackingStatus.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # if true, it means the tracker abandon to track the object. 4 | bool is_lost 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/VectorArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32 vector_dim 3 | float64[] data 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/msg/WeightedPoseArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32[] weights 3 | geometry_msgs/PoseArray poses 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | jsk_recognition_msgs 4 | 1.2.5 5 | ROS messages for jsk_pcl_ros and jsk_perception. 6 | 7 | http://github.com/jsk-ros-pkg/jsk_recognition 8 | http://github.com/jsk-ros-pkg/jsk_recognition/issues 9 | http://wiki.ros.org/jsk_recognition_msgs 10 | 11 | Ryohei Ueda 12 | BSD 13 | catkin 14 | pcl_msgs 15 | pcl_msgs 16 | std_msgs 17 | std_msgs 18 | geometry_msgs 19 | geometry_msgs 20 | sensor_msgs 21 | sensor_msgs 22 | message_generation 23 | message_generation 24 | jsk_footstep_msgs 25 | jsk_footstep_msgs 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/sample/sample_object_array_publisher.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | latch: true 7 | objects: 8 | - id: 1 9 | name: avery_binder 10 | class_id: 1 11 | class_name: book 12 | image_resources: 13 | - package://jsk_arc2017_common/data/objects/avery_binder/top.jpg 14 | mesh_resource: package://jsk_arc2017_common/data/objects/avery_binder/mesh/mesh.obj 15 | weight: 0.382 16 | dimensions: 17 | x: 0.266 18 | y: 0.294 19 | z: 0.041 20 | - id: 18 21 | name: hinged_ruled_index_cards 22 | class_id: 1 23 | class_name: book 24 | image_resources: 25 | - package://jsk_arc2017_common/data/objects/hinged_ruled_index_cards/top.jpg 26 | mesh_resource: package://jsk_arc2017_common/data/objects/hinged_ruled_index_cards/mesh/mesh.obj 27 | weight: 0.098 28 | dimensions: 29 | x: 0.104 30 | y: 0.127 31 | z: 0.022 32 | - id: 35 33 | name: tennis_ball_container 34 | class_id: 2 35 | class_name: cylinder 36 | image_resources: 37 | - package://jsk_arc2017_common/data/objects/tennis_ball_container/top.jpg 38 | mesh_resource: package://jsk_arc2017_common/data/objects/tennis_ball_container/mesh/mesh.obj 39 | weight: 0.217 40 | dimensions: 41 | x: 0.077 42 | y: 0.218 43 | z: 0.077 44 | 45 | 46 | 47 | 48 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/scripts/object_array_publisher.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import rospy 4 | import genpy 5 | from jsk_recognition_msgs.msg import Object 6 | from jsk_recognition_msgs.msg import ObjectArray 7 | 8 | 9 | class ObjectArrayPublisher(object): 10 | 11 | def __init__(self): 12 | objects = rospy.get_param('~objects') 13 | self.msg = ObjectArray() 14 | for obj in objects: 15 | obj_msg = Object() 16 | genpy.message.fill_message_args(obj_msg, obj) 17 | self.msg.objects.append(obj_msg) 18 | 19 | latch = rospy.get_param('~latch', False) 20 | self._pub = rospy.Publisher('~output', ObjectArray, queue_size=1, 21 | latch=True) 22 | self._timer = rospy.Timer(rospy.Duration(1), self._timer_cb, 23 | oneshot=latch) 24 | 25 | def _timer_cb(self, event): 26 | self.msg.header.stamp = event.current_real 27 | self._pub.publish(self.msg) 28 | 29 | 30 | if __name__ == '__main__': 31 | rospy.init_node('object_array_publisher') 32 | app = ObjectArrayPublisher() 33 | rospy.spin() 34 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/scripts/people_pose_array_to_pose_array.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | from geometry_msgs.msg import PoseArray 4 | from jsk_topic_tools import ConnectionBasedTransport 5 | import rospy 6 | 7 | from jsk_recognition_msgs.msg import PeoplePoseArray 8 | 9 | 10 | class PeoplePoseArrayToPoseArray(ConnectionBasedTransport): 11 | 12 | def __init__(self): 13 | super(PeoplePoseArrayToPoseArray, self).__init__() 14 | self.pub = self.advertise('~output', PoseArray, queue_size=1) 15 | 16 | def subscribe(self): 17 | self.sub = rospy.Subscriber('~input', PeoplePoseArray, self._cb) 18 | 19 | def unsubscribe(self): 20 | self.sub.unregister() 21 | 22 | def _cb(self, msg): 23 | out_msg = PoseArray() 24 | for person_pose in msg.poses: 25 | out_msg.poses.extend(person_pose.poses) 26 | out_msg.header = msg.header 27 | self.pub.publish(out_msg) 28 | 29 | 30 | if __name__ == '__main__': 31 | rospy.init_node('people_pose_array_to_pose_array') 32 | app = PeoplePoseArrayToPoseArray() 33 | rospy.spin() 34 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/scripts/plot_data_to_csv.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import rospy 4 | from jsk_recognition_msgs.msg import PlotData 5 | import csv 6 | 7 | counter = 0 8 | def callback(msg): 9 | global counter 10 | rospy.loginfo("writing to %s" % (filename % counter)) 11 | with open(filename % counter, "w") as f: 12 | writer = csv.writer(f, delimiter=',') 13 | writer.writerow(["x", "y"]) 14 | for x, y in zip(msg.xs, msg.ys): 15 | writer.writerow([x, y]) 16 | rospy.loginfo("done") 17 | counter = counter + 1 18 | 19 | if __name__ == "__main__": 20 | rospy.init_node("plot_data_to_csv") 21 | filename = rospy.get_param("~filename", "output_%04d.csv") 22 | sub = rospy.Subscriber("~input", PlotData, callback, queue_size=1) 23 | rospy.spin() 24 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/scripts/save_mesh_server.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import rospy 4 | from jsk_recognition_msgs.msg import BoundingBox 5 | from jsk_recognition_msgs.srv import SaveMesh 6 | from jsk_recognition_msgs.srv import SaveMeshRequest 7 | from std_srvs.srv import Empty 8 | from std_srvs.srv import EmptyResponse 9 | 10 | 11 | class SaveMeshServer(object): 12 | 13 | def __init__(self): 14 | self.ground_frame_id = rospy.get_param('~ground_frame_id', '') 15 | self.sub_bbox = rospy.Subscriber('~input/bbox', BoundingBox, self._cb) 16 | self.srv_client = rospy.ServiceProxy('~save_mesh', SaveMesh) 17 | self.srv_server = rospy.Service('~request', Empty, self._request_cb) 18 | self.bbox_msg = None 19 | 20 | def _cb(self, bbox_msg): 21 | self.bbox_msg = bbox_msg 22 | 23 | def _request_cb(self, req): 24 | if self.bbox_msg is None: 25 | rospy.logerr('No bounding box is set, so ignoring the request.') 26 | return EmptyResponse() 27 | 28 | req = SaveMeshRequest() 29 | req.box = self.bbox_msg 30 | req.ground_frame_id = self.ground_frame_id 31 | self.srv_client.call(req) 32 | return EmptyResponse() 33 | 34 | 35 | if __name__ == '__main__': 36 | rospy.init_node('save_mesh_server') 37 | server = SaveMeshServer() 38 | rospy.spin() 39 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/CallPolygon.srv: -------------------------------------------------------------------------------- 1 | string filename 2 | --- 3 | geometry_msgs/PolygonStamped points 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/CallSnapIt.srv: -------------------------------------------------------------------------------- 1 | jsk_recognition_msgs/SnapItRequest request 2 | --- 3 | geometry_msgs/Pose transformation 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/CheckCircle.srv: -------------------------------------------------------------------------------- 1 | geometry_msgs/Point point 2 | --- 3 | bool clicked 4 | int32 index 5 | string msg 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/CheckCollision.srv: -------------------------------------------------------------------------------- 1 | sensor_msgs/JointState joint 2 | geometry_msgs/PoseStamped pose 3 | --- 4 | bool result 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/EnvironmentLock.srv: -------------------------------------------------------------------------------- 1 | --- 2 | uint32 environment_id 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/EuclideanSegment.srv: -------------------------------------------------------------------------------- 1 | sensor_msgs/PointCloud2 input 2 | float32 tolerance 3 | --- 4 | sensor_msgs/PointCloud2[] output 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/ICPAlign.srv: -------------------------------------------------------------------------------- 1 | sensor_msgs/PointCloud2 reference_cloud 2 | sensor_msgs/PointCloud2 target_cloud 3 | --- 4 | jsk_recognition_msgs/ICPResult result 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/ICPAlignWithBox.srv: -------------------------------------------------------------------------------- 1 | sensor_msgs/PointCloud2 target_cloud 2 | jsk_recognition_msgs/BoundingBox target_box 3 | --- 4 | jsk_recognition_msgs/ICPResult result 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/NonMaximumSuppression.srv: -------------------------------------------------------------------------------- 1 | jsk_recognition_msgs/Rect[] rect 2 | float32 threshold 3 | --- 4 | jsk_recognition_msgs/Rect[] bbox 5 | int64 bbox_count 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/PolygonOnEnvironment.srv: -------------------------------------------------------------------------------- 1 | uint32 environment_id 2 | uint32 plane_index 3 | geometry_msgs/PolygonStamped polygon 4 | --- 5 | bool result 6 | string reason 7 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/RobotPickupReleasePoint.srv: -------------------------------------------------------------------------------- 1 | Header header 2 | geometry_msgs/Point target_point 3 | byte pick_or_release # 0 -> pick, 1 -> release 4 | --- 5 | bool success 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/SaveMesh.srv: -------------------------------------------------------------------------------- 1 | string ground_frame_id # to create solid model 2 | jsk_recognition_msgs/BoundingBox box # to crop mesh 3 | --- 4 | bool success 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/SetDepthCalibrationParameter.srv: -------------------------------------------------------------------------------- 1 | jsk_recognition_msgs/DepthCalibrationParameter parameter 2 | --- 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/SetLabels.srv: -------------------------------------------------------------------------------- 1 | int64[] labels 2 | --- 3 | bool success 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/SetPointCloud2.srv: -------------------------------------------------------------------------------- 1 | sensor_msgs/PointCloud2 cloud 2 | string name 3 | --- 4 | string output 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/SetTemplate.srv: -------------------------------------------------------------------------------- 1 | string type 2 | sensor_msgs/Image image 3 | # dimensions of the texture in the real world (in meters) 4 | float32 dimx 5 | float32 dimy 6 | geometry_msgs/Pose relativepose # used to set the coordinate system of the object relative to the texture 7 | string savefilename # if not empty, will save the resulting pp file to here 8 | --- 9 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/SnapFootstep.srv: -------------------------------------------------------------------------------- 1 | jsk_footstep_msgs/FootstepArray input 2 | --- 3 | jsk_footstep_msgs/FootstepArray output 4 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/SwitchTopic.srv: -------------------------------------------------------------------------------- 1 | # new topics 2 | string camera_info 3 | string points 4 | --- 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/TowerPickUp.srv: -------------------------------------------------------------------------------- 1 | int32 tower_index 2 | --- 3 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/TowerRobotMoveCommand.srv: -------------------------------------------------------------------------------- 1 | # a service to move robot with tower index 2 | byte ROBOT1=1 3 | byte ROBOT2=2 4 | byte ROBOT3=3 5 | 6 | byte PLATE_SMALL=1 7 | byte PLATE_MIDDLE=2 8 | byte PLATE_LARGE=3 9 | 10 | byte TOWER_LOWEST=1 11 | byte TOWER_MIDDLE=2 12 | byte TOWER_HIGHEST=3 13 | byte TOWER_LOWEST2=1 14 | 15 | byte OPTION_NONE=0 16 | byte OPTION_MOVE_INITIAL=1 17 | 18 | int32 robot_index 19 | int32 plate_index 20 | int32 from_tower 21 | int32 to_tower 22 | int32 option_command 23 | --- 24 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/TransformScreenpoint.srv: -------------------------------------------------------------------------------- 1 | # screen point 2 | float32 x 3 | float32 y 4 | bool no_update 5 | --- 6 | # position in actual world 7 | std_msgs/Header header 8 | geometry_msgs/Point point 9 | geometry_msgs/Vector3 vector 10 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/UpdateOffset.srv: -------------------------------------------------------------------------------- 1 | # UpdatePose.srv 2 | # This service is designed to specify localization 3 | # transformation manually 4 | geometry_msgs/TransformStamped transformation 5 | --- 6 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/WhiteBalance.srv: -------------------------------------------------------------------------------- 1 | float32[3] reference_color 2 | sensor_msgs/Image input 3 | --- 4 | sensor_msgs/Image output 5 | -------------------------------------------------------------------------------- /custom_msgs/jsk_recognition_msgs/srv/WhiteBalancePoints.srv: -------------------------------------------------------------------------------- 1 | float32[3] reference_color 2 | sensor_msgs/PointCloud2 input 3 | --- 4 | sensor_msgs/PointCloud2 output 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package vector_map_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.8.0 (2018-08-31) 6 | ------------------ 7 | * [Fix] Moved C++11 flag to autoware_build_flags (`#1395 `_) 8 | * [Feature] Makes sure that all binaries have their dependencies linked (`#1385 `_) 9 | * Contributors: Esteve Fernandez 10 | 11 | 1.7.0 (2018-05-18) 12 | ------------------ 13 | * update Version from 1.6.3 to 1.7.0 in package.xml and CHANGELOG.rst 14 | * -Added support fot VMap colouring to Left Traffic signals (`#988 `_) 15 | -Added Lane number on tlr_superimpose 16 | * Contributors: Abraham Monrroy, Kosuke Murakami 17 | 18 | 1.6.3 (2018-03-06) 19 | ------------------ 20 | 21 | 1.6.2 (2018-02-27) 22 | ------------------ 23 | * Update CHANGELOG 24 | * Contributors: Yusuke FUJII 25 | 26 | 1.6.1 (2018-01-20) 27 | ------------------ 28 | * update CHANGELOG 29 | * Contributors: Yusuke FUJII 30 | 31 | 1.6.0 (2017-12-11) 32 | ------------------ 33 | * Prepare release for 1.6.0 34 | * Add feature of to find stopline. and following minor fixes 35 | - to change vectormap operation to vectormap lib. 36 | - to change state operation 37 | * Contributors: Yamato ANDO, Yusuke FUJII 38 | 39 | 1.5.1 (2017-09-25) 40 | ------------------ 41 | * Release/1.5.1 (`#816 `_) 42 | * fix a build error by gcc version 43 | * fix build error for older indigo version 44 | * update changelog for v1.5.1 45 | * 1.5.1 46 | * Contributors: Yusuke FUJII 47 | 48 | 1.5.0 (2017-09-21) 49 | ------------------ 50 | * Update changelog 51 | * Contributors: Yusuke FUJII 52 | 53 | 1.4.0 (2017-08-04) 54 | ------------------ 55 | * version number must equal current release number so we can start releasing in the future 56 | * added changelogs 57 | * Contributors: Dejan Pangercic 58 | 59 | 1.3.1 (2017-07-16) 60 | ------------------ 61 | 62 | 1.3.0 (2017-07-14) 63 | ------------------ 64 | 65 | 1.2.0 (2017-06-07) 66 | ------------------ 67 | 68 | 1.1.2 (2017-02-27 23:10) 69 | ------------------------ 70 | 71 | 1.1.1 (2017-02-27 22:25) 72 | ------------------------ 73 | 74 | 1.1.0 (2017-02-24) 75 | ------------------ 76 | 77 | 1.0.1 (2017-01-14) 78 | ------------------ 79 | 80 | 1.0.0 (2016-12-22) 81 | ------------------ 82 | * Add message_runtime dependency 83 | * Add vector_map library 84 | * Contributors: syouji 85 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(vector_map_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | autoware_build_flags 6 | std_msgs 7 | message_generation 8 | ) 9 | 10 | set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") 11 | 12 | add_message_files( 13 | FILES 14 | Point.msg 15 | PointArray.msg 16 | Vector.msg 17 | VectorArray.msg 18 | Line.msg 19 | LineArray.msg 20 | Area.msg 21 | AreaArray.msg 22 | Pole.msg 23 | PoleArray.msg 24 | Box.msg 25 | BoxArray.msg 26 | DTLane.msg 27 | DTLaneArray.msg 28 | Node.msg 29 | NodeArray.msg 30 | Lane.msg 31 | LaneArray.msg 32 | WayArea.msg 33 | WayAreaArray.msg 34 | RoadEdge.msg 35 | RoadEdgeArray.msg 36 | Gutter.msg 37 | GutterArray.msg 38 | Curb.msg 39 | CurbArray.msg 40 | WhiteLine.msg 41 | WhiteLineArray.msg 42 | StopLine.msg 43 | StopLineArray.msg 44 | ZebraZone.msg 45 | ZebraZoneArray.msg 46 | CrossWalk.msg 47 | CrossWalkArray.msg 48 | RoadMark.msg 49 | RoadMarkArray.msg 50 | RoadPole.msg 51 | RoadPoleArray.msg 52 | RoadSign.msg 53 | RoadSignArray.msg 54 | Signal.msg 55 | SignalArray.msg 56 | StreetLight.msg 57 | StreetLightArray.msg 58 | UtilityPole.msg 59 | UtilityPoleArray.msg 60 | GuardRail.msg 61 | GuardRailArray.msg 62 | SideWalk.msg 63 | SideWalkArray.msg 64 | DriveOnPortion.msg 65 | DriveOnPortionArray.msg 66 | CrossRoad.msg 67 | CrossRoadArray.msg 68 | SideStrip.msg 69 | SideStripArray.msg 70 | CurveMirror.msg 71 | CurveMirrorArray.msg 72 | Wall.msg 73 | WallArray.msg 74 | Fence.msg 75 | FenceArray.msg 76 | RailCrossing.msg 77 | RailCrossingArray.msg 78 | ) 79 | 80 | generate_messages( 81 | DEPENDENCIES 82 | std_msgs 83 | ) 84 | 85 | catkin_package( 86 | CATKIN_DEPENDS message_runtime std_msgs 87 | ) 88 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Area.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 aid 3 | int32 slid 4 | int32 elid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/AreaArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Area[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Box.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 bid 3 | int32 pid1 4 | int32 pid2 5 | int32 pid3 6 | int32 pid4 7 | float64 height 8 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/BoxArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Box[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/CrossRoad.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 aid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/CrossRoadArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | CrossRoad[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/CrossWalk.msg: -------------------------------------------------------------------------------- 1 | # type 2 | uint8 CLOSURE_LINE=0 3 | uint8 STRIPE_PATTERN=1 4 | uint8 BICYCLE_LANE=2 5 | 6 | # Ver 1.00 7 | int32 id 8 | int32 aid 9 | int32 type 10 | int32 bdid 11 | int32 linkid 12 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/CrossWalkArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | CrossWalk[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Curb.msg: -------------------------------------------------------------------------------- 1 | # dir 2 | uint8 RIGHT=0 3 | uint8 LEFT=1 4 | 5 | # Ver 1.00 6 | int32 id 7 | int32 lid 8 | float64 height 9 | float64 width 10 | int32 dir 11 | int32 linkid 12 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/CurbArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Curb[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/CurveMirror.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.10 2 | int32 id 3 | int32 vid 4 | int32 plid 5 | int32 type # differ from specification 6 | int32 linkid 7 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/CurveMirrorArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | CurveMirror[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/DTLane.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 did 3 | float64 dist 4 | int32 pid 5 | float64 dir 6 | float64 apara 7 | float64 r 8 | float64 slope 9 | float64 cant 10 | float64 lw 11 | float64 rw 12 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/DTLaneArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | DTLane[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/DriveOnPortion.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.10 2 | int32 id 3 | int32 aid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/DriveOnPortionArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | DriveOnPortion[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Fence.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.10 2 | int32 id 3 | int32 aid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/FenceArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Fence[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/GuardRail.msg: -------------------------------------------------------------------------------- 1 | # type 2 | uint8 PLATE_BLADE=0 3 | uint8 POLE=1 4 | 5 | # Ver 1.00 6 | int32 id 7 | int32 aid 8 | int32 type 9 | int32 linkid 10 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/GuardRailArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | GuardRail[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Gutter.msg: -------------------------------------------------------------------------------- 1 | # type 2 | uint8 NO_COVER=0 3 | uint8 COVER=1 4 | uint8 GRATING=2 5 | 6 | # Ver 1.00 7 | int32 id 8 | int32 aid 9 | int32 type 10 | int32 linkid 11 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/GutterArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Gutter[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Lane.msg: -------------------------------------------------------------------------------- 1 | # jct 2 | uint8 NORMAL=0 3 | uint8 LEFT_BRANCHING=1 4 | uint8 RIGHT_BRANCHING=2 5 | uint8 LEFT_MERGING=3 6 | uint8 RIGHT_MERGING=4 7 | uint8 COMPOSITION=5 8 | 9 | # lanetype 10 | uint8 STRAIGHT=0 11 | uint8 LEFT_TURN=1 12 | uint8 RIGHT_TURN=2 13 | 14 | # lanecfgfg 15 | uint8 PASS=0 16 | uint8 FAIL=1 17 | 18 | # Ver 1.00 19 | int32 lnid 20 | int32 did 21 | int32 blid 22 | int32 flid 23 | int32 bnid 24 | int32 fnid 25 | int32 jct 26 | int32 blid2 27 | int32 blid3 28 | int32 blid4 29 | int32 flid2 30 | int32 flid3 31 | int32 flid4 32 | int32 clossid 33 | float64 span 34 | int32 lcnt 35 | int32 lno 36 | 37 | # Ver 1.20 38 | int32 lanetype 39 | int32 limitvel 40 | int32 refvel 41 | int32 roadsecid 42 | int32 lanecfgfg 43 | int32 linkwaid 44 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/LaneArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Lane[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Line.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 lid 3 | int32 bpid 4 | int32 fpid 5 | int32 blid 6 | int32 flid 7 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/LineArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Line[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Node.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 nid 3 | int32 pid 4 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/NodeArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Node[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Point.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 pid 3 | float64 b 4 | float64 l 5 | float64 h 6 | float64 bx 7 | float64 ly 8 | int32 ref 9 | int32 mcode1 10 | int32 mcode2 11 | int32 mcode3 12 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/PointArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Point[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Pole.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 plid 3 | int32 vid 4 | float64 length 5 | float64 dim 6 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/PoleArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Pole[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RailCrossing.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 aid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RailCrossingArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | RailCrossing[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RoadEdge.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 lid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RoadEdgeArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | RoadEdge[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RoadMark.msg: -------------------------------------------------------------------------------- 1 | # type 2 | uint8 MARK=1 3 | uint8 ARROW=2 4 | uint8 CHARACTER=3 5 | uint8 SIGN=4 6 | 7 | # Ver 1.00 8 | int32 id 9 | int32 aid 10 | int32 type # differ from specification 11 | int32 linkid 12 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RoadMarkArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | RoadMark[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RoadPole.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 plid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RoadPoleArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | RoadPole[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RoadSign.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 vid 4 | int32 plid 5 | int32 type # differ from specification 6 | int32 linkid 7 | 8 | ## Optional specification 9 | int32 TYPE_NULL = 0 10 | int32 TYPE_STOP = 1 11 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/RoadSignArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | RoadSign[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/SideStrip.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.10 2 | int32 id 3 | int32 lid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/SideStripArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | SideStrip[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/SideWalk.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 aid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/SideWalkArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | SideWalk[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Signal.msg: -------------------------------------------------------------------------------- 1 | # type 2 | uint8 RED=1 3 | uint8 BLUE=2 #Green (outside Japan) 4 | uint8 YELLOW=3 5 | uint8 PEDESTRIAN_RED=4 6 | uint8 PEDESTRIAN_BLUE=5 7 | uint8 OTHER=9 8 | 9 | # Ver 1.00 10 | int32 id 11 | int32 vid 12 | int32 plid 13 | int32 type 14 | int32 linkid 15 | 16 | # left turn 17 | uint8 RED_LEFT=21 18 | uint8 BLUE_LEFT=22 #Green (outside Japan) 19 | uint8 YELLOW_LEFT=23 20 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/SignalArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Signal[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/StopLine.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 lid 4 | int32 tlid 5 | int32 signid 6 | int32 linkid 7 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/StopLineArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | StopLine[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/StreetLight.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 lid 4 | int32 plid 5 | int32 linkid 6 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/StreetLightArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | StreetLight[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/UtilityPole.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 plid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/UtilityPoleArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | UtilityPole[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Vector.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 vid 3 | int32 pid 4 | float64 hang 5 | float64 vang 6 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/VectorArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Vector[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/Wall.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.10 2 | int32 id 3 | int32 aid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/WallArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Wall[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/WayArea.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.20 2 | int32 waid 3 | int32 aid 4 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/WayAreaArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | WayArea[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/WhiteLine.msg: -------------------------------------------------------------------------------- 1 | # type 2 | uint8 SOLID_LINE=0 3 | uint8 DASHED_LINE_SOLID=1 4 | uint8 DASHED_LINE_BLANK=2 5 | 6 | # Ver 1.00 7 | int32 id 8 | int32 lid 9 | float64 width 10 | int8 color # W:White / Y:Yellow 11 | int32 type 12 | int32 linkid 13 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/WhiteLineArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | WhiteLine[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/ZebraZone.msg: -------------------------------------------------------------------------------- 1 | # Ver 1.00 2 | int32 id 3 | int32 aid 4 | int32 linkid 5 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/msg/ZebraZoneArray.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | ZebraZone[] data 3 | -------------------------------------------------------------------------------- /custom_msgs/vector_map_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | vector_map_msgs 4 | 1.8.0 5 | The vector_map_msgs package 6 | syouji 7 | BSD 8 | catkin 9 | autoware_build_flags 10 | std_msgs 11 | message_generation 12 | std_msgs 13 | message_runtime 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(visualization_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | ImageMarker.msg 10 | InteractiveMarker.msg 11 | InteractiveMarkerControl.msg 12 | InteractiveMarkerFeedback.msg 13 | InteractiveMarkerInit.msg 14 | InteractiveMarkerPose.msg 15 | InteractiveMarkerUpdate.msg 16 | MarkerArray.msg 17 | Marker.msg 18 | MenuEntry.msg 19 | ) 20 | 21 | generate_messages(DEPENDENCIES geometry_msgs std_msgs) 22 | 23 | catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs) 24 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b visualization_msgs is a package to collect all visualization-related messages into one place. 6 | 7 | The messages it currently contains are: 8 | - \ref visualization_msgs::Marker 9 | - \ref visualization_msgs::MarkerArray 10 | - \ref visualization_msgs::ImageMarker 11 | - \ref visualization_msgs::Polyline 12 | 13 | */ -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/ImageMarker.msg: -------------------------------------------------------------------------------- 1 | uint8 CIRCLE=0 2 | uint8 LINE_STRIP=1 3 | uint8 LINE_LIST=2 4 | uint8 POLYGON=3 5 | uint8 POINTS=4 6 | 7 | uint8 ADD=0 8 | uint8 REMOVE=1 9 | 10 | Header header 11 | string ns # namespace, used with id to form a unique id 12 | int32 id # unique id within the namespace 13 | int32 type # CIRCLE/LINE_STRIP/etc. 14 | int32 action # ADD/REMOVE 15 | geometry_msgs/Point position # 2D, in pixel-coords 16 | float32 scale # the diameter for a circle, etc. 17 | std_msgs/ColorRGBA outline_color 18 | uint8 filled # whether to fill in the shape with color 19 | std_msgs/ColorRGBA fill_color # color [0.0-1.0] 20 | duration lifetime # How long the object should last before being automatically deleted. 0 means forever 21 | 22 | 23 | geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords 24 | std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc. -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/InteractiveMarker.msg: -------------------------------------------------------------------------------- 1 | # Time/frame info. 2 | # If header.time is set to 0, the marker will be retransformed into 3 | # its frame on each timestep. You will receive the pose feedback 4 | # in the same frame. 5 | # Otherwise, you might receive feedback in a different frame. 6 | # For rviz, this will be the current 'fixed frame' set by the user. 7 | Header header 8 | 9 | # Initial pose. Also, defines the pivot point for rotations. 10 | geometry_msgs/Pose pose 11 | 12 | # Identifying string. Must be globally unique in 13 | # the topic that this message is sent through. 14 | string name 15 | 16 | # Short description (< 40 characters). 17 | string description 18 | 19 | # Scale to be used for default controls (default=1). 20 | float32 scale 21 | 22 | # All menu and submenu entries associated with this marker. 23 | MenuEntry[] menu_entries 24 | 25 | # List of controls displayed for this marker. 26 | InteractiveMarkerControl[] controls 27 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/InteractiveMarkerFeedback.msg: -------------------------------------------------------------------------------- 1 | # Time/frame info. 2 | Header header 3 | 4 | # Identifying string. Must be unique in the topic namespace. 5 | string client_id 6 | 7 | # Feedback message sent back from the GUI, e.g. 8 | # when the status of an interactive marker was modified by the user. 9 | 10 | # Specifies which interactive marker and control this message refers to 11 | string marker_name 12 | string control_name 13 | 14 | # Type of the event 15 | # KEEP_ALIVE: sent while dragging to keep up control of the marker 16 | # MENU_SELECT: a menu entry has been selected 17 | # BUTTON_CLICK: a button control has been clicked 18 | # POSE_UPDATE: the pose has been changed using one of the controls 19 | uint8 KEEP_ALIVE = 0 20 | uint8 POSE_UPDATE = 1 21 | uint8 MENU_SELECT = 2 22 | uint8 BUTTON_CLICK = 3 23 | 24 | uint8 MOUSE_DOWN = 4 25 | uint8 MOUSE_UP = 5 26 | 27 | uint8 event_type 28 | 29 | # Current pose of the marker 30 | # Note: Has to be valid for all feedback types. 31 | geometry_msgs/Pose pose 32 | 33 | # Contains the ID of the selected menu entry 34 | # Only valid for MENU_SELECT events. 35 | uint32 menu_entry_id 36 | 37 | # If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point 38 | # may contain the 3 dimensional position of the event on the 39 | # control. If it does, mouse_point_valid will be true. mouse_point 40 | # will be relative to the frame listed in the header. 41 | geometry_msgs/Point mouse_point 42 | bool mouse_point_valid 43 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/InteractiveMarkerInit.msg: -------------------------------------------------------------------------------- 1 | # Identifying string. Must be unique in the topic namespace 2 | # that this server works on. 3 | string server_id 4 | 5 | # Sequence number. 6 | # The client will use this to detect if it has missed a subsequent 7 | # update. Every update message will have the same sequence number as 8 | # an init message. Clients will likely want to unsubscribe from the 9 | # init topic after a successful initialization to avoid receiving 10 | # duplicate data. 11 | uint64 seq_num 12 | 13 | # All markers. 14 | InteractiveMarker[] markers 15 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/InteractiveMarkerPose.msg: -------------------------------------------------------------------------------- 1 | # Time/frame info. 2 | Header header 3 | 4 | # Initial pose. Also, defines the pivot point for rotations. 5 | geometry_msgs/Pose pose 6 | 7 | # Identifying string. Must be globally unique in 8 | # the topic that this message is sent through. 9 | string name 10 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/InteractiveMarkerUpdate.msg: -------------------------------------------------------------------------------- 1 | # Identifying string. Must be unique in the topic namespace 2 | # that this server works on. 3 | string server_id 4 | 5 | # Sequence number. 6 | # The client will use this to detect if it has missed an update. 7 | uint64 seq_num 8 | 9 | # Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE. 10 | # UPDATE: Incremental update to previous state. 11 | # The sequence number must be 1 higher than for 12 | # the previous update. 13 | # KEEP_ALIVE: Indicates the that the server is still living. 14 | # The sequence number does not increase. 15 | # No payload data should be filled out (markers, poses, or erases). 16 | uint8 KEEP_ALIVE = 0 17 | uint8 UPDATE = 1 18 | 19 | uint8 type 20 | 21 | #Note: No guarantees on the order of processing. 22 | # Contents must be kept consistent by sender. 23 | 24 | #Markers to be added or updated 25 | InteractiveMarker[] markers 26 | 27 | #Poses of markers that should be moved 28 | InteractiveMarkerPose[] poses 29 | 30 | #Names of markers to be erased 31 | string[] erases 32 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/Marker.msg: -------------------------------------------------------------------------------- 1 | # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz 2 | 3 | uint8 ARROW=0 4 | uint8 CUBE=1 5 | uint8 SPHERE=2 6 | uint8 CYLINDER=3 7 | uint8 LINE_STRIP=4 8 | uint8 LINE_LIST=5 9 | uint8 CUBE_LIST=6 10 | uint8 SPHERE_LIST=7 11 | uint8 POINTS=8 12 | uint8 TEXT_VIEW_FACING=9 13 | uint8 MESH_RESOURCE=10 14 | uint8 TRIANGLE_LIST=11 15 | 16 | uint8 ADD=0 17 | uint8 MODIFY=0 18 | uint8 DELETE=2 19 | uint8 DELETEALL=3 20 | 21 | Header header # header for time/frame information 22 | string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object 23 | int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later 24 | int32 type # Type of object 25 | int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects 26 | geometry_msgs/Pose pose # Pose of the object 27 | geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) 28 | std_msgs/ColorRGBA color # Color [0.0-1.0] 29 | duration lifetime # How long the object should last before being automatically deleted. 0 means forever 30 | bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep 31 | 32 | #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) 33 | geometry_msgs/Point[] points 34 | #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) 35 | #number of colors must either be 0 or equal to the number of points 36 | #NOTE: alpha is not yet used 37 | std_msgs/ColorRGBA[] colors 38 | 39 | # NOTE: only used for text markers 40 | string text 41 | 42 | # NOTE: only used for MESH_RESOURCE markers 43 | string mesh_resource 44 | bool mesh_use_embedded_materials 45 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/MarkerArray.msg: -------------------------------------------------------------------------------- 1 | Marker[] markers 2 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/msg/MenuEntry.msg: -------------------------------------------------------------------------------- 1 | # MenuEntry message. 2 | 3 | # Each InteractiveMarker message has an array of MenuEntry messages. 4 | # A collection of MenuEntries together describe a 5 | # menu/submenu/subsubmenu/etc tree, though they are stored in a flat 6 | # array. The tree structure is represented by giving each menu entry 7 | # an ID number and a "parent_id" field. Top-level entries are the 8 | # ones with parent_id = 0. Menu entries are ordered within their 9 | # level the same way they are ordered in the containing array. Parent 10 | # entries must appear before their children. 11 | 12 | # Example: 13 | # - id = 3 14 | # parent_id = 0 15 | # title = "fun" 16 | # - id = 2 17 | # parent_id = 0 18 | # title = "robot" 19 | # - id = 4 20 | # parent_id = 2 21 | # title = "pr2" 22 | # - id = 5 23 | # parent_id = 2 24 | # title = "turtle" 25 | # 26 | # Gives a menu tree like this: 27 | # - fun 28 | # - robot 29 | # - pr2 30 | # - turtle 31 | 32 | # ID is a number for each menu entry. Must be unique within the 33 | # control, and should never be 0. 34 | uint32 id 35 | 36 | # ID of the parent of this menu entry, if it is a submenu. If this 37 | # menu entry is a top-level entry, set parent_id to 0. 38 | uint32 parent_id 39 | 40 | # menu / entry title 41 | string title 42 | 43 | # Arguments to command indicated by command_type (below) 44 | string command 45 | 46 | # Command_type stores the type of response desired when this menu 47 | # entry is clicked. 48 | # FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. 49 | # ROSRUN: execute "rosrun" with arguments given in the command field (above). 50 | # ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). 51 | uint8 FEEDBACK=0 52 | uint8 ROSRUN=1 53 | uint8 ROSLAUNCH=2 54 | uint8 command_type 55 | -------------------------------------------------------------------------------- /custom_msgs/visualization_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | visualization_msgs 3 | 1.12.7 4 | 5 | visualization_msgs is a set of messages used by higher level packages, such as rviz, that deal in visualization-specific data. 6 | 7 | The main messages in visualization_msgs is visualization_msgs/Marker. 8 | The marker message is used to send visualization "markers" such as boxes, spheres, arrows, lines, etc. to a visualization environment such as rviz. 9 | See the rviz tutorial rviz tutorials for more information. 10 | 11 | Tully Foote 12 | BSD 13 | 14 | http://ros.org/wiki/visualization_msgs 15 | Josh Faust 16 | Davis Gossow 17 | 18 | catkin 19 | 20 | geometry_msgs 21 | message_generation 22 | std_msgs 23 | 24 | geometry_msgs 25 | message_runtime 26 | std_msgs 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /docs/en/helptoc.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | Autoware Toolbox 4 | Installation 5 | ROS node samples 6 | 7 | Functions - By Category 8 | Helper 9 | addCustomMessageFolderToSearchPath - Add ROS custom messages for Autoware to MATLAB search path 10 | createCustomMessages - Generate ROS custom messages for Autoware in MATLAB format 11 | editJavaClassPath - Add jar file path to javaclasspath.txt 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /docs/en/helptoc_en.md: -------------------------------------------------------------------------------- 1 | # Autoware Toolbox 2 | 3 | 1. [Installation](install_awtb_en.html) 4 | 2. [Autoware Tooolbox Examples](./samples/demos_en.md) 5 | 3. [Function Reference](./awtb_functions_by_cat_en.html) 6 | -------------------------------------------------------------------------------- /docs/en/images/addon_explore_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/addon_explore_en.png -------------------------------------------------------------------------------- /docs/en/images/after_rosgenmsg_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/after_rosgenmsg_en.png -------------------------------------------------------------------------------- /docs/en/images/agree_license_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/agree_license_en.png -------------------------------------------------------------------------------- /docs/en/images/autoware_messages_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/autoware_messages_en.png -------------------------------------------------------------------------------- /docs/en/images/install_if_ros_custom_msg_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/install_if_ros_custom_msg_en.png -------------------------------------------------------------------------------- /docs/en/images/java_heap_memory_preferences_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/java_heap_memory_preferences_en.png -------------------------------------------------------------------------------- /docs/en/images/javaclasspath_txt_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/javaclasspath_txt_en.png -------------------------------------------------------------------------------- /docs/en/images/run_setup_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/run_setup_en.png -------------------------------------------------------------------------------- /docs/en/images/third_party_software_en.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/images/third_party_software_en.png -------------------------------------------------------------------------------- /docs/en/info.xml: -------------------------------------------------------------------------------- 1 | 3 | 4 | 5 | 2018a 6 | Autoware Toolbox (en) 7 | links_targets 8 | 9 | ./ 10 | 11 | -------------------------------------------------------------------------------- /docs/en/samples/Detection/acf_detector_ml_en.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/acf_detector_ml_en.m -------------------------------------------------------------------------------- /docs/en/samples/Detection/acf_detector_sl_en.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/acf_detector_sl_en.m -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/acf_detector_sl_top.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/acf_detector_sl_top.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/add_new_pannel.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/add_new_pannel.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/click_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/click_rviz.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/detect_people.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/detect_people.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/move_image_viewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/move_image_viewer.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/play_simulation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/play_simulation.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/resize_image_viewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/resize_image_viewer.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/rosgraph_acf_detector_ml.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/rosgraph_acf_detector_ml.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/rosgraph_acf_detector_sl.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/rosgraph_acf_detector_sl.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/AcfDetector/select_image_viewer_plugin.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/AcfDetector/select_image_viewer_plugin.png -------------------------------------------------------------------------------- /docs/en/samples/Detection/images/set_rosbag.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Detection/images/set_rosbag.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/click_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/click_rviz.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/load_vehicle_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/load_vehicle_model.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/map_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/map_tab.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/ndt_matching_app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/ndt_matching_app.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/replay_rosbag.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/replay_rosbag.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/run_autoware.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/run_autoware.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/runtime_manager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/runtime_manager.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/set_baselink_to_localizer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/set_baselink_to_localizer.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/set_computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/set_computing_tab.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/set_localizer_velodyne.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/set_localizer_velodyne.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/set_plane_number.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/set_plane_number.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/set_rosbag.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/set_rosbag.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/show_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/show_rviz.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/simulation_clock_on.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/simulation_clock_on.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/voxel_grid_filter_ml/filtered_points.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/voxel_grid_filter_ml/filtered_points.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/voxel_grid_filter_ml/points_raw.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/voxel_grid_filter_ml/points_raw.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/voxel_grid_filter_ml/rosgraph_voxel_grid_filter_ml.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/voxel_grid_filter_ml/rosgraph_voxel_grid_filter_ml.png -------------------------------------------------------------------------------- /docs/en/samples/Filters/images/voxel_grid_filter_ml/show_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Filters/images/voxel_grid_filter_ml/show_rviz.png -------------------------------------------------------------------------------- /docs/en/samples/Localization/images/2D_Pose_Estimate.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Localization/images/2D_Pose_Estimate.png -------------------------------------------------------------------------------- /docs/en/samples/Localization/images/result_waypoint_follower.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Localization/images/result_waypoint_follower.png -------------------------------------------------------------------------------- /docs/en/samples/Localization/images/vel_pose_connect/computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Localization/images/vel_pose_connect/computing_tab.png -------------------------------------------------------------------------------- /docs/en/samples/Localization/images/vel_pose_connect/rosgraph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Localization/images/vel_pose_connect/rosgraph.png -------------------------------------------------------------------------------- /docs/en/samples/Localization/images/vel_pose_connect/sl_rosgraph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Localization/images/vel_pose_connect/sl_rosgraph.png -------------------------------------------------------------------------------- /docs/en/samples/Localization/images/vel_pose_connect/vel_pose_connect_sl_top.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Localization/images/vel_pose_connect/vel_pose_connect_sl_top.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/2D_Pose_Estimate.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/2D_Pose_Estimate.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/pure_pursuit/computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/pure_pursuit/computing_tab.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/pure_pursuit/pure_pursuit_sl_top.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/pure_pursuit/pure_pursuit_sl_top.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/pure_pursuit/rosgraph_pure_pursuit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/pure_pursuit/rosgraph_pure_pursuit.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/pure_pursuit/wf_simulator_app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/pure_pursuit/wf_simulator_app.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/result_waypoint_follower.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/result_waypoint_follower.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/twist_filter/computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/twist_filter/computing_tab.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/twist_filter/rosgraph_twist_filter.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/twist_filter/rosgraph_twist_filter.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/twist_filter/twist_filter_sl_top.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/twist_filter/twist_filter_sl_top.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/twist_filter/wf_simulator_app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/twist_filter/wf_simulator_app.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/vel_pose_connect.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/vel_pose_connect.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/wf_simulator/computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/wf_simulator/computing_tab.png -------------------------------------------------------------------------------- /docs/en/samples/Planning/images/wf_simulator/rosgraph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/Planning/images/wf_simulator/rosgraph.png -------------------------------------------------------------------------------- /docs/en/samples/demos_en.md: -------------------------------------------------------------------------------- 1 | # Provided ROS Node Examples 2 | 3 | ## MATLAB ROS Node Examples 4 | |module|node|Description| 5 | |:--|:--|:--| 6 | |Detection|[ACF Detector](./Detection/acf_detector_ml_en.md)|Detecting people using aggregate channel features (ACF).| 7 | | |[LiDAR Euclidean Track](./Detection/lidar_euclidean_track_ml_en.md)| | 8 | | |[Vision Dummy Track](./Detection/vision_dummy_track_ml_en.md)| | 9 | |Localization|[Vel pose connect](./Localization/vel_pose_connect_ml_en.md)|Determining the velocity and pose of the vehicle.| 10 | |Mission Planning|[Lane Stop](./Planning/lane_stop_ml_en.md)|Selecting waypoints according to the signal color.| 11 | |Motion Planning|[Path Select](./Planning/path_select_ml_en.md)|Generating final waypoints from temporal waypoints.| 12 | | |[Wf Simulator](./Planning/wf_simulator_ml_en.md)| | 13 | |Filters|[Voxel Grid Filter](./Filters/voxel_grid_filter_ml_en.md)|Downsampling point cloud using a voxel grid filter.| 14 | | |[Random Filter](./Filters/demo_random_filter_ml_en.md)|Downsampling point cloud with random sampling and without replacement.| 15 | | |[Nonuniform Voxel Grid Filte](./Filters/nonuniformgrid_filter_ml_en.md)|Downsampling point cloud using nonuniform voxel grid filter.| 16 | | |[Fog rectification](./Filters/fog_rectification_ml_en.md)|Producing defogged image.| 17 | 18 | ## Simulink ROS Node Examples 19 | |module|node|Description| 20 | |:--|:--|:--| 21 | |Detection|[ACF Detector](./Detection/acf_detector_sl_en.md)|Detecting people using aggregate channel features (ACF).| 22 | | |[Vision Dummy Track](./Detection/vision_dummy_track_sl_en.md)| | 23 | |Localization|[Vel pose connect](./Localization/vel_pose_connect_sl_en.md)|Determining the velocity and pose of the vehicle.| 24 | |Mission Planning|[Lane Stop](./Planning/lane_stop_sl_en.md)|Selecting waypoints according to the signal color.| 25 | |Motion Planning|[Path Select](./Planning/path_select_sl_en.md)|Generating final waypoints from temporal waypoints.| 26 | | |[Pure Pursuit](./Planning/pure_pursuit_sl_en.md)|Generating the actuation commands for the autonomous vehicle.| 27 | | |[Twist filter](./Planning/twist_filter_sl_en.md)|Filtering the received actuation command.| 28 | -------------------------------------------------------------------------------- /docs/en/samples/images/choose_file_to_open.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/choose_file_to_open.png -------------------------------------------------------------------------------- /docs/en/samples/images/click_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/click_rviz.png -------------------------------------------------------------------------------- /docs/en/samples/images/connect_ros_master.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/connect_ros_master.png -------------------------------------------------------------------------------- /docs/en/samples/images/map_tab_load_vectormap_tf.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/map_tab_load_vectormap_tf.png -------------------------------------------------------------------------------- /docs/en/samples/images/rosinit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/rosinit.png -------------------------------------------------------------------------------- /docs/en/samples/images/run_autoware.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/run_autoware.png -------------------------------------------------------------------------------- /docs/en/samples/images/runtime_manager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/runtime_manager.png -------------------------------------------------------------------------------- /docs/en/samples/images/rviz_file_open_config.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/rviz_file_open_config.png -------------------------------------------------------------------------------- /docs/en/samples/images/setup_tab_load_vehicle_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/setup_tab_load_vehicle_model.png -------------------------------------------------------------------------------- /docs/en/samples/images/show_vectormap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/show_vectormap.png -------------------------------------------------------------------------------- /docs/en/samples/images/waypoint_loader.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/waypoint_loader.png -------------------------------------------------------------------------------- /docs/en/samples/images/wf_simulator_app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/en/samples/images/wf_simulator_app.png -------------------------------------------------------------------------------- /docs/ja/helptoc.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | Autoware Toolbox (ja) 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | Autoware Tooolbox のインストール (Installation) 15 | Autoware Tooolbox 内の Autoware ノードサンプル 16 | 17 | 18 | 19 | 20 | 21 | カテゴリ別関数リファレンス (Function Reference) 22 | 23 | Helper 24 | addCustomMessageFolderToSearchPath - Autoware用ROSカスタムメッセージをMATLAB検索パスに登録 25 | createCustomMessages - Autoware用ROSカスタムメッセージをMATLAB形式で生成 26 | editJavaClassPath - javaclasspath.txt にjarファイルパスを追加 27 | 28 | その他 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /docs/ja/helptoc_ja.md: -------------------------------------------------------------------------------- 1 | # Autoware Toolbox 2 | 3 | 1. [Autoware Tooolbox のインストール (Installation)](install_awtb_ja.md) 4 | 2. [Autoware Tooolbox 内の Autoware ノードサンプル](./samples/demos_ja.md) 5 | 3. [カテゴリ別関数リファレンス (Function Reference)](./awtb_functions_by_cat_ja.html) 6 | -------------------------------------------------------------------------------- /docs/ja/images/addon_explore.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/addon_explore.png -------------------------------------------------------------------------------- /docs/ja/images/after_rosgenmsg.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/after_rosgenmsg.png -------------------------------------------------------------------------------- /docs/ja/images/agree_license.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/agree_license.png -------------------------------------------------------------------------------- /docs/ja/images/autoware_messages.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/autoware_messages.png -------------------------------------------------------------------------------- /docs/ja/images/chk_rst_if_cstm_msg.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/chk_rst_if_cstm_msg.png -------------------------------------------------------------------------------- /docs/ja/images/input_password.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/input_password.png -------------------------------------------------------------------------------- /docs/ja/images/install_if_ros_custom_msg.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/install_if_ros_custom_msg.png -------------------------------------------------------------------------------- /docs/ja/images/install_process.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/install_process.png -------------------------------------------------------------------------------- /docs/ja/images/installed_message.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/installed_message.png -------------------------------------------------------------------------------- /docs/ja/images/java_heap_memory_preferences.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/java_heap_memory_preferences.png -------------------------------------------------------------------------------- /docs/ja/images/javaclasspath_txt.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/javaclasspath_txt.png -------------------------------------------------------------------------------- /docs/ja/images/not_installed_message.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/not_installed_message.png -------------------------------------------------------------------------------- /docs/ja/images/rosgenmsg.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/rosgenmsg.png -------------------------------------------------------------------------------- /docs/ja/images/run_setup.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/run_setup.png -------------------------------------------------------------------------------- /docs/ja/images/signin_mathworks_acount.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/signin_mathworks_acount.png -------------------------------------------------------------------------------- /docs/ja/images/third_party_software.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/images/third_party_software.png -------------------------------------------------------------------------------- /docs/ja/info.xml: -------------------------------------------------------------------------------- 1 | 3 | 4 | 5 | 2018a 6 | Autoware Toolbox (ja) 7 | links_targets 8 | 9 | ./ 10 | 11 | -------------------------------------------------------------------------------- /docs/ja/samples/Detection/acf_detector_ml_ja.md: -------------------------------------------------------------------------------- 1 | # AcfDetector.m の利用例 2 | 3 | ## 1. Autoware の起動 4 | Autoware を実行して ROS マスターを起動します。 5 | ![](images/run_autoware.png) 6 | 7 | Runtime Manager が立ち上がります。 8 | ![](images/runtime_manager.png) 9 | 10 | ## 2. rviz の起動 11 | Runtime Manager の RViz ボタンをクリックして rviz を起動します。 12 | ![](images/AcfDetector/click_rviz.png) 13 | 14 | ## 3. imageViewerPlugin の表示 15 | rviz が起動したら、メニューの[Panels]-[Add New Panel]を選択します。 16 | ![](images/AcfDetector/add_new_pannel.png) 17 | 18 | 起動した画面で「imageViewerPlugin」を選択します。 19 | ![](images/AcfDetector/select_image_viewer_plugin.png) 20 | 21 | imageViewerPlugin 画面のサイズを調整します。 22 | 例えば、下図のように imageViewerPlugin 画面をフローティング状態にします。 23 | ![](images/AcfDetector/move_image_viewer.png) 24 | 25 | その後、画面サイズを調整します。 26 | ![](images/AcfDetector/resize_image_viewer.png) 27 | 28 | ## 4. 動画再生する rosbag ファイルの設定 29 | Runtime Manager の Simulation タブを開きます。 30 | 「Ref」ボタンをクリックして、再生する rosbag ファイルを設定します。 31 | ![](images/set_rosbag.png) 32 | 33 | ## 5. MATLAB から Autoware(ROS マスター)への接続 34 | MATLAB で rosinit コマンドを使用して ROS マスターに接続します。 35 | rosinit の引数はご自身の環境に合わせて設定してください。 36 | ```MATLAB 37 | rosinit(); 38 | ``` 39 | 40 | ## 6. AcfDetector.m の起動 41 | AcfDetector.m クラスファイルがあるフォルダを MATLAB 検索パスに登録後、 42 | AcfDetector のインスタンスを生成し、人物検出処理を実行します。 43 | ```MATLAB 44 | acf_detector_folder = fullfile(autoware.getRootDirectory(), ... 45 | 'benchmark', 'computing', 'perception', 'detection', ... 46 | 'vision_detector', 'acf_detector'); 47 | addpath(acf_detector_folder); 48 | acf_detector_obj = AcfDetector(); 49 | ``` 50 | 51 | ## 7. rosbag の再生(Runtime Manager の Simulation タブ) 52 | 「Play」ボタンをクリックしてrosbag を再生します。 53 | ![](images/AcfDetector/play_simulation.png) 54 | 55 | ## 8. imageViewerPlugin の Topic 設定 56 | 1. imageViewerPlugin の Image Topic を「/image_raw」に設定します。 57 | 1. imageViewerPlugin の Object Rect Topic を「/detection/vision_objects」に設定します。 58 | 1. 人物を検出すると Boundary Box が表示されます。 59 | 60 | ![](images/AcfDetector/detect_people.png) 61 | 上図は、書籍「[Autoware 自動運転ソフトウェア入門](http://www.ric.co.jp/book/contents/book_1187.html) 」で提供されるサンプルデータを利用しています。 62 | 本サンプル実行時のノードグラフを表示するには、[ここ](images/AcfDetector/rosgraph_acf_detector.png) をクリックしてください。 63 | AcfDetector.m で生成されたノードは **/acf_detector_ml** です。 64 | 65 | ## 9. 終了処理 66 | 下記のコマンドを実行して終了します。 67 | ```MATLAB 68 | acf_detector_obj.delete(); 69 | rosshutdown(); 70 | rmpath(acf_detector_folder); 71 | clear acf_detector_obj acf_detector_folder; 72 | ``` -------------------------------------------------------------------------------- /docs/ja/samples/Detection/acf_detector_sl_ja.md: -------------------------------------------------------------------------------- 1 | # acf_detector_sl.slx の利用例 2 | 3 | ## 1. Autoware の起動 4 | Autoware を実行して ROS マスターを起動します。 5 | ![](images/run_autoware.png) 6 | 7 | Runtime Manager が立ち上がります。 8 | ![](images/runtime_manager.png) 9 | 10 | ## 2. rviz の起動 11 | Runtime Manager の RViz ボタンをクリックして rviz を起動します。 12 | ![](images/AcfDetector/click_rviz.png) 13 | 14 | ## 3. imageViewerPlugin の表示 15 | rviz が起動したら、メニューの[Panels]-[Add New Panel]を選択します。 16 | ![](images/AcfDetector/add_new_pannel.png) 17 | 18 | 起動した画面で「imageViewerPlugin」を選択します。 19 | ![](images/AcfDetector/select_image_viewer_plugin.png) 20 | 21 | imageViewerPlugin 画面のサイズを調整します。 22 | 例えば、下図のように imageViewerPlugin 画面をフローティング状態にします。 23 | ![](images/AcfDetector/move_image_viewer.png) 24 | 25 | その後、画面サイズを調整します。 26 | ![](images/AcfDetector/resize_image_viewer.png) 27 | 28 | ## 4. 動画再生する rosbag ファイルの設定 29 | Runtime Manager の Simulation タブを開きます。 30 | 「Ref」ボタンをクリックして、再生する rosbag ファイルを設定します。 31 | ![](images/set_rosbag.png) 32 | 33 | ## 5. MATLAB から Autoware(ROS マスター)への接続 34 | MATLAB で rosinit コマンドを使用して ROS マスターに接続します。 35 | rosinit の引数はご自身の環境に合わせて設定してください。 36 | ```MATLAB 37 | rosinit(); 38 | ``` 39 | 40 | ## 6. Simulink で作成した ACF Detector(acf_detector_sl.slx)を起動 41 | ACF Detector の Simulink モデル(acf_detector_sl.slx)があるフォルダを MATLAB 検索パスに登録後、 42 | Simulink モデルを開きます。 43 | ```MATLAB 44 | acf_detector_sl_folder = fullfile(autoware.getRootDirectory(), ... 45 | 'benchmark', 'computing', 'perception', ... 46 | 'detection', 'vision_detector', 'acf_detector'); 47 | addpath(acf_detector_sl_folder); 48 | model = 'acf_detector_sl'; 49 | open_system(model); 50 | ``` 51 | 52 | ![](images/AcfDetector/acf_detector_sl_top.png) 53 | 54 | ## 7. Simulink で作成した ACF Detector を実行 55 | ACF Detector の Simulink モデルを実行します。 56 | ```MATLAB 57 | set_param(model, 'SimulationCommand', 'Start'); 58 | ``` 59 | 60 | ## 8. rosbag の再生(Runtime Manager の Simulation タブ) 61 | 62 | 「Play」ボタンをクリックしてrosbag を再生します。 63 | ![](images/AcfDetector/play_simulation.png) 64 | 65 | ## 9. imageViewerPlugin の Topic 設定 66 | 1. imageViewerPlugin の Image Topic を「/image_raw」に設定します。 67 | 1. imageViewerPlugin の Object Rect Topic を「/detection/vision_objects」に設定します。 68 | 1. 人物を検出すると Boundary Box が表示されます。 69 | ![](images/AcfDetector/detect_people.png) 70 | 71 | 上図は、書籍「[自動運転ソフトウェア入門 Autoware](http://www.ric.co.jp/book/contents/book_1187.html)」で提供されるサンプルデータを利用しています。 72 | 本サンプル実行時のノードグラフを表示するには、 73 | [ここ](images/AcfDetector/rosgraph_acf_detector_sl.png) をクリックしてください。 74 | 本例においては、acf_detector_sl.slx で生成されたノードは /acf_detector_sl_81473 です。 75 | 76 | ## 10. 終了処理 77 | 下記のコマンドを実行して終了します。 78 | ```MATLAB 79 | set_param(model, 'SimulationCommand', 'Stop'); 80 | close_system(model); 81 | rosshutdown(); 82 | rmpath(acf_detector_sl_folder); 83 | clear('model', 'acf_detector_sl_folder'); 84 | ``` -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/acf_detector_sl_top.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/acf_detector_sl_top.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/add_new_pannel.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/add_new_pannel.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/click_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/click_rviz.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/detect_people.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/detect_people.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/move_image_viewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/move_image_viewer.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/play_simulation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/play_simulation.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/resize_image_viewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/resize_image_viewer.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/rosgraph_acf_detector.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/rosgraph_acf_detector.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/rosgraph_acf_detector_sl.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/rosgraph_acf_detector_sl.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/AcfDetector/select_image_viewer_plugin.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/AcfDetector/select_image_viewer_plugin.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/run_autoware.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/run_autoware.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/runtime_manager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/runtime_manager.png -------------------------------------------------------------------------------- /docs/ja/samples/Detection/images/set_rosbag.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Detection/images/set_rosbag.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/click_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/click_rviz.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/load_vehicle_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/load_vehicle_model.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/map_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/map_tab.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/ndt_matching_app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/ndt_matching_app.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/replay_rosbag.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/replay_rosbag.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/run_autoware.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/run_autoware.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/runtime_manager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/runtime_manager.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/select_rosbag_file.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/select_rosbag_file.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/set_baselink_to_localizer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/set_baselink_to_localizer.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/set_computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/set_computing_tab.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/set_localizer_velodyne.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/set_localizer_velodyne.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/set_plane_number.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/set_plane_number.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/set_rosbag.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/set_rosbag.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/set_rosbag2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/set_rosbag2.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/show_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/show_rviz.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/simulation_clock_on.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/simulation_clock_on.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/voxel_grid_filter_ml/filtered_points.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/voxel_grid_filter_ml/filtered_points.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/voxel_grid_filter_ml/points_raw.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/voxel_grid_filter_ml/points_raw.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/voxel_grid_filter_ml/rosgraph_voxel_grid_filter_ml.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/voxel_grid_filter_ml/rosgraph_voxel_grid_filter_ml.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/images/voxel_grid_filter_ml/show_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/images/voxel_grid_filter_ml/show_rviz.png -------------------------------------------------------------------------------- /docs/ja/samples/Filters/voxel_grid_filter_ml_ja.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Filters/voxel_grid_filter_ml_ja.m -------------------------------------------------------------------------------- /docs/ja/samples/Localization/images/2D_Pose_Estimate.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Localization/images/2D_Pose_Estimate.png -------------------------------------------------------------------------------- /docs/ja/samples/Localization/images/result_waypoint_follower.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Localization/images/result_waypoint_follower.png -------------------------------------------------------------------------------- /docs/ja/samples/Localization/images/rosinit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Localization/images/rosinit.png -------------------------------------------------------------------------------- /docs/ja/samples/Localization/images/vel_pose_connect/computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Localization/images/vel_pose_connect/computing_tab.png -------------------------------------------------------------------------------- /docs/ja/samples/Localization/images/vel_pose_connect/rosgraph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Localization/images/vel_pose_connect/rosgraph.png -------------------------------------------------------------------------------- /docs/ja/samples/Localization/images/vel_pose_connect/run_vel_pose_connect.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Localization/images/vel_pose_connect/run_vel_pose_connect.png -------------------------------------------------------------------------------- /docs/ja/samples/Localization/images/vel_pose_connect/sl_rosgraph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Localization/images/vel_pose_connect/sl_rosgraph.png -------------------------------------------------------------------------------- /docs/ja/samples/Localization/images/vel_pose_connect/vel_pose_connect_sl_top.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Localization/images/vel_pose_connect/vel_pose_connect_sl_top.PNG -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/2D_Pose_Estimate.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/2D_Pose_Estimate.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/pure_pursuit/computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/pure_pursuit/computing_tab.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/pure_pursuit/pure_pursuit_sl_top.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/pure_pursuit/pure_pursuit_sl_top.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/pure_pursuit/rosgraph_pure_pursuit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/pure_pursuit/rosgraph_pure_pursuit.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/pure_pursuit/wf_simulator_app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/pure_pursuit/wf_simulator_app.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/result_waypoint_follower.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/result_waypoint_follower.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/twist_filter/computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/twist_filter/computing_tab.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/twist_filter/rosgraph_twist_filter.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/twist_filter/rosgraph_twist_filter.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/twist_filter/twist_filter_sl_top.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/twist_filter/twist_filter_sl_top.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/twist_filter/wf_simulator_app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/twist_filter/wf_simulator_app.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/vel_pose_connect.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/vel_pose_connect.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/wf_simulator/computing_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/wf_simulator/computing_tab.png -------------------------------------------------------------------------------- /docs/ja/samples/Planning/images/wf_simulator/rosgraph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/Planning/images/wf_simulator/rosgraph.png -------------------------------------------------------------------------------- /docs/ja/samples/demos_ja.md: -------------------------------------------------------------------------------- 1 | # Autoware Toolbox で提供されている Autoware の ROS ノードの例 2 | 3 | ## MATLAB で作成した Autoware の ROSノード 4 | |module|node|Description| 5 | |:--|:--|:--| 6 | |Detection|[ACF Detector](./Detection/acf_detector_ml_ja.md)|Detecting people using aggregate channel features (ACF).| 7 | | |[LiDAR Euclidean Track](./Detection/lidar_euclidean_track_ml_ja.md)| | 8 | | |[Vision Dummy Track](./Detection/vision_dummy_track_ml_ja.md)| | 9 | |Localization|[Vel pose connect](./Localization/vel_pose_connect_ml_ja.md)|Determining the velocity and pose of the vehicle.| 10 | |Mission Planning|[Lane Stop](./Planning/lane_stop_ml_ja.md)|Selecting waypoints according to the signal color.| 11 | |Motion Planning|[Path Select](./Planning/path_select_ml_ja.md)|Generating final waypoints from temporal waypoints.| 12 | | |[Wf Simulator](./Planning/wf_simulator_ml_ja.md)| | 13 | |Filters|[Voxel Grid Filter](./Filters/voxel_grid_filter_ml_ja.md)|Downsampling point cloud using a voxel grid filter.| 14 | | |[Random Filter](./Filters/demo_random_filter_ml_ja.md)|Downsampling point cloud with random sampling and without replacement.| 15 | | |[Nonuniform Voxel Grid Filte](./Filters/nonuniformgrid_filter_ml_ja.md)|Downsampling point cloud using nonuniform voxel grid filter.| 16 | | |[Fog rectification](./Filters/fog_rectification_ml_ja.md)|Producing defogged image.| 17 | 18 | ## Simulink で作成した Autoware の ROS ノード 19 | |module|node|Description| 20 | |:--|:--|:--| 21 | |Detection|[ACF Detector](./Detection/acf_detector_sl_ja.md)|Detecting people using aggregate channel features (ACF).| 22 | | |[Vision Dummy Track](./Detection/vision_dummy_track_sl_ja.md)| | 23 | |Localization|[Vel pose connect](./Localization/vel_pose_connect_sl_ja.md)|Determining the velocity and pose of the vehicle.| 24 | |Mission Planning|[Lane Stop](./Planning/lane_stop_sl_ja.md)|Selecting waypoints according to the signal color.| 25 | |Motion Planning|[Path Select](./Planning/path_select_sl_ja.md)|Generating final waypoints from temporal waypoints.| 26 | | |[Pure Pursuit](./Planning/pure_pursuit_sl_ja.md)|Generating the actuation commands for the autonomous vehicle.| 27 | | |[Twist filter](./Planning/twist_filter_sl_ja.md)|Filtering the received actuation command.| 28 | -------------------------------------------------------------------------------- /docs/ja/samples/images/choose_file_to_open.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/choose_file_to_open.png -------------------------------------------------------------------------------- /docs/ja/samples/images/click_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/click_rviz.png -------------------------------------------------------------------------------- /docs/ja/samples/images/connect_ros_master.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/connect_ros_master.png -------------------------------------------------------------------------------- /docs/ja/samples/images/map_tab_load_vectormap_tf.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/map_tab_load_vectormap_tf.png -------------------------------------------------------------------------------- /docs/ja/samples/images/rosinit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/rosinit.png -------------------------------------------------------------------------------- /docs/ja/samples/images/run_autoware.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/run_autoware.png -------------------------------------------------------------------------------- /docs/ja/samples/images/runtime_manager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/runtime_manager.png -------------------------------------------------------------------------------- /docs/ja/samples/images/rviz_file_open_config.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/rviz_file_open_config.png -------------------------------------------------------------------------------- /docs/ja/samples/images/setup_tab_load_vehicle_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/setup_tab_load_vehicle_model.png -------------------------------------------------------------------------------- /docs/ja/samples/images/show_vectormap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/show_vectormap.png -------------------------------------------------------------------------------- /docs/ja/samples/images/waypoint_loader.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/waypoint_loader.png -------------------------------------------------------------------------------- /docs/ja/samples/images/wf_simulator_app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/CPFL/Autoware_Toolbox/e065db9e680ad01e846a1c89e0265bf5d824f38d/docs/ja/samples/images/wf_simulator_app.png --------------------------------------------------------------------------------