└── src
├── msgs
├── hadmap_msgs
│ ├── msg
│ │ ├── Map.msg
│ │ ├── MapPolyCoeff.msg
│ │ ├── LocalMapSection.msg
│ │ ├── MapReferLine.msg
│ │ ├── MapSection.msg
│ │ ├── Point.msg
│ │ ├── MapSplineCoeff.msg
│ │ ├── MapLane.msg
│ │ ├── LocalMapPoint.msg
│ │ ├── Section.msg
│ │ ├── LocalMapLane.msg
│ │ └── Lane.msg
│ ├── CHANGELOG.rst
│ ├── srv
│ │ └── LocalMap.srv
│ ├── package.xml
│ └── CMakeLists.txt
├── simulator_msgs
│ ├── msg
│ │ ├── Rate.msg
│ │ └── SetState.msg
│ ├── package.xml
│ └── CMakeLists.txt
├── localization_msgs
│ ├── msg
│ │ ├── StopPoints.msg
│ │ ├── LidarLoc.msg
│ │ └── StopPoint.msg
│ ├── package.xml
│ └── CMakeLists.txt
├── center_msgs
│ ├── msg
│ │ ├── DestPoint.msg
│ │ ├── Ack.msg
│ │ ├── TruckArrived.msg
│ │ ├── VehicleStopAccurate.msg
│ │ ├── CalibrateSwitch.msg
│ │ ├── GlobalPath.msg
│ │ ├── TruckPose.msg
│ │ ├── PlcStopCmd.msg
│ │ ├── VehicleTarget.msg
│ │ ├── TosTarget.msg
│ │ └── ExternalCenterCmd.msg
│ ├── package.xml
│ └── CMakeLists.txt
├── pnc_msgs
│ ├── msg
│ │ ├── ForceVehicleCmd.msg
│ │ ├── WayPoint.msg
│ │ ├── VehicleState.msg
│ │ ├── TruckState.msg
│ │ ├── Gear.msg
│ │ ├── VirtualWall.msg
│ │ ├── PlanningCmd.msg
│ │ ├── VehicleOtherCmd.msg
│ │ ├── VehicleCmd.msg
│ │ ├── DecisionCmd.msg
│ │ ├── VehicleOtherInfo.msg
│ │ ├── VehicleInfo.msg
│ │ └── GNSSInfo.msg
│ ├── package.xml
│ └── CMakeLists.txt
├── perception_msgs
│ ├── msg
│ │ ├── Objects.msg
│ │ └── Object.msg
│ ├── package.xml
│ └── CMakeLists.txt
├── conti_radar_msgs
│ ├── msg
│ │ ├── conti_Objects.msg
│ │ └── conti_Object.msg
│ ├── package.xml
│ └── CMakeLists.txt
└── raw_sensor_msgs
│ ├── msg
│ └── GnssImuInfo.msg
│ ├── package.xml
│ └── CMakeLists.txt
├── sensor_visualizer.tar.gz
├── conti_radar
├── lib
│ └── can
│ │ └── libCanCmd.so
├── README.md
├── tool
│ └── conti_radar_node.cpp
├── config
│ ├── default.yaml
│ ├── byd.yaml
│ ├── cciv.yaml
│ ├── cs55.yaml
│ ├── foton.yaml
│ ├── sinotruk_c7.yaml
│ └── sinotruk_t5g.yaml
├── src
│ ├── conti_radar
│ │ ├── object_list_status_60a.cpp
│ │ ├── CMakeLists.txt
│ │ ├── object_general_info_60b.cpp
│ │ ├── object_extended_info_60d.cpp
│ │ ├── radar_state_201.cpp
│ │ └── object_quality_info_60c.cpp
│ ├── radar_can.cpp
│ └── radar_can_conti.cpp
├── include
│ ├── conti_radar
│ │ ├── object_list_status_60a.h
│ │ ├── object_general_info_60b.h
│ │ ├── object_extended_info_60d.h
│ │ ├── radar_state_201.h
│ │ ├── object_quality_info_60c.h
│ │ └── ICANCmd.h
│ ├── radar_can.h
│ └── radar_can_conti.h
├── launch
│ └── run_conti_radar.launch
├── package.xml
└── CMakeLists.txt
├── radar_visualizer
├── launch
│ └── radar_visualizer.launch
├── tool
│ └── radar_visualizer_node.cpp
├── include
│ └── radar_visualizer.h
├── src
│ └── radar_visualizer.cpp
├── package.xml
└── CMakeLists.txt
└── CMakeLists.txt
/src/msgs/hadmap_msgs/msg/Map.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | Section[] sections
3 |
--------------------------------------------------------------------------------
/src/msgs/simulator_msgs/msg/Rate.msg:
--------------------------------------------------------------------------------
1 | float64 cycle_us
2 | float64 time_rate
3 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/MapPolyCoeff.msg:
--------------------------------------------------------------------------------
1 | float64 offset
2 | float64[] poly_parameters
3 |
--------------------------------------------------------------------------------
/src/msgs/localization_msgs/msg/StopPoints.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | StopPoint[] stop_points
3 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/DestPoint.msg:
--------------------------------------------------------------------------------
1 | int32 truckId
2 |
3 | geometry_msgs/Point destPoint
4 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/LocalMapSection.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | LocalMapLane[] lanes
3 |
4 |
5 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/ForceVehicleCmd.msg:
--------------------------------------------------------------------------------
1 | Header header
2 |
3 | float64 stop_distance_err
4 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/Ack.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | string chid
3 | int32 recv_packet_id
4 |
5 |
6 |
--------------------------------------------------------------------------------
/src/msgs/localization_msgs/msg/LidarLoc.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | int32 id
3 | geometry_msgs/Transform pose
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/WayPoint.msg:
--------------------------------------------------------------------------------
1 | float64 x
2 | float64 y
3 | float64 z
4 | float64 heading
5 | float64 curvature
6 |
--------------------------------------------------------------------------------
/src/sensor_visualizer.tar.gz:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zbzb00zbzb/catkin_radar/HEAD/src/sensor_visualizer.tar.gz
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/TruckArrived.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | string chid
3 | bool arrived
4 |
5 | int32 send_packet_id
6 |
--------------------------------------------------------------------------------
/src/msgs/perception_msgs/msg/Objects.msg:
--------------------------------------------------------------------------------
1 | Header header
2 |
3 | uint64 second
4 | uint64 fra_second
5 | Object[] objects
6 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/VehicleState.msg:
--------------------------------------------------------------------------------
1 | Header header
2 |
3 | geometry_msgs/Transform pose
4 | geometry_msgs/Twist velocity
5 |
--------------------------------------------------------------------------------
/src/conti_radar/lib/can/libCanCmd.so:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zbzb00zbzb/catkin_radar/HEAD/src/conti_radar/lib/can/libCanCmd.so
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/TruckState.msg:
--------------------------------------------------------------------------------
1 | Header header
2 |
3 | pnc_msgs/VehicleState truck_head
4 | pnc_msgs/VehicleState[] trailers
5 |
--------------------------------------------------------------------------------
/src/msgs/conti_radar_msgs/msg/conti_Objects.msg:
--------------------------------------------------------------------------------
1 | Header header
2 |
3 | uint64 second
4 | uint64 fra_second
5 | conti_Object[] objects
6 |
--------------------------------------------------------------------------------
/src/conti_radar/README.md:
--------------------------------------------------------------------------------
1 | # Function Description
2 |
3 | radar node get object information via can card and publish them in type of perception_msgs
4 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/MapReferLine.msg:
--------------------------------------------------------------------------------
1 |
2 | geometry_msgs/Point start_point
3 | float64 heading
4 | float64 length
5 | MapSplineCoeff spline_coeff
6 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/MapSection.msg:
--------------------------------------------------------------------------------
1 | Header header
2 |
3 | uint32 id
4 | float64 s
5 |
6 | MapReferLine refer_line
7 | MapPolyCoeff[] z_coeffs
8 | MapLane[] lanes
9 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/VehicleStopAccurate.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | string chid
3 | int32 send_packet_id
4 | int32 stop_tag_id
5 | uint8 stop_tag_type
6 | float64 stop_offset
7 |
--------------------------------------------------------------------------------
/src/radar_visualizer/launch/radar_visualizer.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/Point.msg:
--------------------------------------------------------------------------------
1 | int32 id
2 |
3 | geometry_msgs/Point point
4 |
5 |
6 |
7 | ## not used
8 |
9 | float32 heading
10 | float64 delta_s
11 | uint8 property
12 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/MapSplineCoeff.msg:
--------------------------------------------------------------------------------
1 | float64 start_offset
2 | uint8 degree
3 | uint8 dimension
4 | float64 scale
5 | float64[] spline_knots
6 | geometry_msgs/Point[] spline_points
7 |
8 |
--------------------------------------------------------------------------------
/src/msgs/simulator_msgs/msg/SetState.msg:
--------------------------------------------------------------------------------
1 | float64 x # m
2 | float64 y # m
3 | float64 z # m
4 | float64 heading_ang # rad
5 | float64 speed # m/s
6 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/CalibrateSwitch.msg:
--------------------------------------------------------------------------------
1 | uint8 STOP_CALIBRATE = 0
2 | uint8 START_CALIBRATE = 1
3 |
4 | Header header
5 | string chid
6 | int32 stop_tag_id
7 | uint8 stop_tag_type
8 | uint8 calibrate_switch
9 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/GlobalPath.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | string chid
3 |
4 | geometry_msgs/Point src_point
5 | geometry_msgs/Point dest_point
6 | int32[] paths
7 |
8 | int32 recv_packet_id
9 | int32 send_packet_id
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/MapLane.msg:
--------------------------------------------------------------------------------
1 | uint8 lane_type
2 |
3 | MapPolyCoeff[] poly_coeffs
4 |
5 |
6 | int16 predecessor
7 | int16 successor
8 |
9 | float32 lane_residual_len
10 | float32 speed_limit
11 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/TruckPose.msg:
--------------------------------------------------------------------------------
1 | # truck register
2 | uint8 TRUNK_UNREGISTER = 0
3 | uint8 TRUNK_REGISTER = 1
4 |
5 | Header header
6 | string chid
7 | geometry_msgs/Transform pose
8 | int32 recv_packet_id
9 | int32 send_packet_id
10 | uint8 trunk_register
11 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/CHANGELOG.rst:
--------------------------------------------------------------------------------
1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2 | Changelog for package hadmap_msgs
3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4 |
5 | 0.0.1 (2017-11-04)
6 | ------------------
7 | * add msg
8 | * for hadmap_msgs
9 | * Initial commit
10 | * Contributors: coolhebei
11 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/LocalMapPoint.msg:
--------------------------------------------------------------------------------
1 | uint8 TYPE_CROSS = 0
2 | uint8 TYPE_NOT_CROSS = 1
3 |
4 | # lane point localization
5 | geometry_msgs/Point point
6 | # heading angle
7 | float32 heading
8 | # now: cross or not
9 | uint8 type
10 | # speed limit
11 | float32 speed_limit
12 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/srv/LocalMap.srv:
--------------------------------------------------------------------------------
1 | # current localization
2 | geometry_msgs/Transform transform
3 | # query length before us
4 | float32 query_len_ahead
5 | # query length after us
6 | float32 query_len_behind
7 |
8 | ---
9 |
10 | # timestamp
11 | Header header
12 | # all lanes
13 | LocalMapLane[] lanes
14 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/PlcStopCmd.msg:
--------------------------------------------------------------------------------
1 | # PLC Expected direction
2 | uint8 TRUCK_NONE_CMD = 0
3 | uint8 TRUCK_STOP = 1
4 | uint8 TRUCK_MOVE_FORWARD = 2
5 | uint8 TRUCK_MOVE_BACKWARD = 3
6 |
7 | Header header
8 | uint8 expected_direction
9 | int32 expected_distances
10 |
11 | int32 send_packet_id
12 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/VehicleTarget.msg:
--------------------------------------------------------------------------------
1 | uint8 TAG_ON_ANQIAO = 1
2 | uint8 TAG_ON_CHANGQIAO = 2
3 |
4 | Header header
5 | int32 send_packet_id
6 | string chid
7 | geometry_msgs/Point stop_point
8 | int32 stop_tag_id
9 | uint8 stop_tag_type
10 | float64 brake_distance
11 | float64 hadmap_stop_shift
12 | float64 tag_stop_shift
13 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/Section.msg:
--------------------------------------------------------------------------------
1 | uint8 TYPE_NORMAL = 0
2 | uint8 TYPE_CROSS_BEFORE = 1
3 | uint8 TYPE_CROSS_AFTER = 2
4 | uint8 TYPE_CROSS_BEFORE_AND_AFTER = 3
5 |
6 |
7 | int32 id
8 | Lane[] lanes
9 | int32[] predecessors
10 | int32[] successors
11 | uint8 type #
12 |
13 | float64[] stop_distances
14 |
15 |
16 |
17 |
18 |
--------------------------------------------------------------------------------
/src/msgs/localization_msgs/msg/StopPoint.msg:
--------------------------------------------------------------------------------
1 |
2 | # main key
3 | int32 id
4 |
5 | # distance, [0, unlimit]
6 | float64 distance_shift
7 |
8 |
9 | float64 angle # rad
10 | float64 distance_vertical
11 |
12 |
13 |
14 | uint8 TYPE_CRANE = 0
15 | uint8 TYPE_YARD = 1
16 | uint8 TYPE_OTHER = 2
17 |
18 | # type
19 | uint8 type
20 |
21 |
22 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/LocalMapLane.msg:
--------------------------------------------------------------------------------
1 | # lane id
2 | int32 id
3 | # residual length
4 | float32 residual_len
5 |
6 | float32 stopline_distance
7 | geometry_msgs/Point stopline
8 |
9 | # central planning points
10 | LocalMapPoint[] center
11 | # left boundary
12 | LocalMapPoint[] left
13 | # right boundary
14 | LocalMapPoint[] right
15 |
16 |
17 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/Gear.msg:
--------------------------------------------------------------------------------
1 | uint8 GEAR_P = 0
2 | uint8 GEAR_R = 1
3 | uint8 GEAR_N = 2
4 | uint8 GEAR_D = 3
5 | uint8 GEAR_1 = 4
6 | uint8 GEAR_2 = 5
7 | uint8 GEAR_3 = 6
8 | uint8 GEAR_4 = 7
9 | uint8 GEAR_5 = 8
10 | uint8 GEAR_6 = 9
11 | uint8 GEAR_7 = 10
12 | uint8 GEAR_8 = 11
13 | uint8 GEAR_9 = 12
14 | uint8 GEAR_10 = 13
15 | uint8 GEAR_11 = 14
16 | uint8 GEAR_12 = 15
17 |
18 |
19 | uint8 value
20 |
--------------------------------------------------------------------------------
/src/conti_radar/tool/conti_radar_node.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 |
6 | #include "radar_can_conti.h"
7 |
8 | int main(int argc, char **argv)
9 | {
10 | ros::init(argc, argv, "conti_radar_node");
11 |
12 | RadarCan *radar_can = new RadarCan_Conti;
13 |
14 | radar_can->setup();
15 | radar_can->doListening();
16 |
17 | delete radar_can;
18 |
19 | return 0;
20 | }
21 |
--------------------------------------------------------------------------------
/src/conti_radar/config/default.yaml:
--------------------------------------------------------------------------------
1 | # 0 for left, 1 for middle, 2 for right
2 |
3 | #freqency to read from can card
4 | recv_info_freq: 100
5 |
6 | #not use yet
7 | max_missing_times: 100
8 |
9 | #freqency to check if we have received vehicle_msgs/radar_msgs/gnss_msgs...
10 | #actual timeout time: 1 / $(arg check_msg_freg) * 10 = 1s
11 | check_msg_freq: 10
12 |
13 | #//freqency to send vehicle_msgs: speed, yaw_rate
14 | send_req_vehicle_msg_freq: 50
--------------------------------------------------------------------------------
/src/radar_visualizer/tool/radar_visualizer_node.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-12.
3 | //
4 |
5 | #include "radar_visualizer.h"
6 |
7 |
8 | int main(int argc, char **argv)
9 | {
10 | ros::init(argc, argv, "radar_visualizer");
11 |
12 | RadarVisualizer *radarvisualizer = new RadarVisualizer;
13 |
14 | radarvisualizer->init();
15 | radarvisualizer->doListening();
16 |
17 |
18 | delete(radarvisualizer);
19 |
20 | return 0;
21 | }
22 |
23 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/TosTarget.msg:
--------------------------------------------------------------------------------
1 | # truck status
2 | uint8 INNER_FORM_LOGIN = 0
3 | uint8 INNER_FORM_TRUCK_IDLE = 1
4 | uint8 INNER_FORM_TRUCK_EMPTY_TO_ORIGIN = 2
5 | uint8 INNER_FORM_TRUCK_EMPTY_AT_ORIGIN = 3
6 | uint8 INNER_FORM_TRUCK_LADEN_TO_DEST = 4
7 | uint8 INNER_FORM_TRUCK_LADEN_AT_DEST = 5
8 |
9 |
10 | Header header
11 | string chid
12 | string truck_pos
13 | string transfer_zone
14 | int32 container_type
15 |
16 | int32 send_packet_id
17 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/msg/Lane.msg:
--------------------------------------------------------------------------------
1 |
2 |
3 | int32 id
4 |
5 | Point pt_start
6 | Point pt_end
7 |
8 | int32[] predecessors
9 | int32[] successors
10 |
11 | Point[] pts_center
12 | Point[] pts_left
13 | Point[] pts_right
14 |
15 | float64[] len_integral
16 |
17 |
18 | float64 speed_limit
19 |
20 |
21 | ## not used
22 |
23 | uint8 line_left_type
24 | uint8 line_right_type
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 | ## dynamic
34 |
35 | int32 resign_id
36 | float32 residual_len
37 |
--------------------------------------------------------------------------------
/src/conti_radar/src/conti_radar/object_list_status_60a.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #include "object_list_status_60a.h"
6 |
7 | ObjectListStatus60A::ObjectListStatus60A()
8 | {
9 | num_of_obj = -1;
10 | }
11 |
12 | void ObjectListStatus60A::unPackBytes(const CAN_DataFrame& can_frame)
13 | {
14 | num_of_obj = (uint8_t)(can_frame.arryData[0]);
15 | }
16 |
17 | int ObjectListStatus60A::getNumOfObj()
18 | {
19 | return num_of_obj;
20 | }
21 |
22 |
23 |
24 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/msg/ExternalCenterCmd.msg:
--------------------------------------------------------------------------------
1 | uint8 EXTERNAL_LATERAL_NO_CMD = 0
2 | uint8 EXTERNAL_LATERAL_KEEP_IN_LANE = 1
3 | uint8 EXTERNAL_LATERAL_BYPASS_IN_LANE = 2
4 | uint8 EXTERNAL_LATERAL_CHANGE_TO_LEFT = 3
5 | uint8 EXTERNAL_LATERAL_CHANGE_TO_RIGHT = 4
6 |
7 | uint8 EXTERNAL_SPEED_NO_CMD = 0
8 | uint8 EXTERNAL_SPEED_FREE = 1
9 | uint8 EXTERNAL_SPEED_FOLLOW = 2
10 | uint8 EXTERNAL_SPEED_ESTOP = 3
11 |
12 | Header header
13 | int32 send_packet_id
14 | int8 lateral_cmd
15 | int8 speed_cmd
16 |
--------------------------------------------------------------------------------
/src/conti_radar/src/conti_radar/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_library(conti_radar_lib
2 | object_extended_info_60d.cpp
3 | object_quality_info_60c.cpp
4 | object_general_info_60b.cpp
5 | object_list_status_60a.cpp
6 | radar_state_201.cpp
7 | )
8 |
9 | install(TARGETS conti_radar_lib
10 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
11 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
12 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
--------------------------------------------------------------------------------
/src/msgs/conti_radar_msgs/msg/conti_Object.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header
2 |
3 | int8 Object_NofObjects
4 |
5 | int8 ID
6 | float64 Object_DistLong
7 | float64 Object_DistLat
8 | float64 Object_VrelLong
9 | float64 Object_VrelLat
10 | int32 Object_DynProp
11 | float64 Object_RCS
12 | int32 Obj_ProbOfExist
13 |
14 | float64 Object_OrientationAngel
15 | float64 Object_Length
16 | float64 Object_Width
17 |
18 |
19 | geometry_msgs/Point object_box_center
20 | geometry_msgs/Point object_box_size
21 |
22 |
23 |
--------------------------------------------------------------------------------
/src/conti_radar/include/conti_radar/object_list_status_60a.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #ifndef CONTI_RADAR_OBJECT_LIST_STATUS_60A_H
6 | #define CONTI_RADAR_OBJECT_LIST_STATUS_60A_H
7 |
8 | #include
9 | #include "ICANCmd.h"
10 |
11 | class ObjectListStatus60A
12 | {
13 | private:
14 | int num_of_obj;
15 | public:
16 | ObjectListStatus60A();
17 | void unPackBytes(const CAN_DataFrame& can_frame);
18 | int getNumOfObj();
19 | };
20 |
21 | #endif //CONTI_RADAR_OBJECT_LIST_STATUS_60A_H
22 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/VirtualWall.msg:
--------------------------------------------------------------------------------
1 | uint8 VIRTUAL_WALL_TYPE_UNKNOWN = 0
2 | uint8 VIRTUAL_WALL_TYPE_STOPLINE = 1
3 | uint8 VIRTUAL_WALL_TYPE_OBSTACLE = 2
4 | uint8 VIRTUAL_WALL_TYPE_OBSTACLE_VIRTUAL = 3
5 | uint8 VIRTUAL_WALL_TYPE_OCCUPANCY_GRID = 4
6 | uint8 VIRTUAL_WALL_TYPE_STOPLINE_TAG = 5
7 | uint8 VIRTUAL_WALL_TYPE_STOPLINE_PLC = 6
8 |
9 | uint8 virtual_wall_type
10 | uint32 virtual_wall_id
11 | float64 follow_second
12 | float64 follow_distance
13 | float64 follow_speed
14 | float64 follow_acceleration # Optional
15 |
16 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/PlanningCmd.msg:
--------------------------------------------------------------------------------
1 | uint8 MODE_AUTO = 0
2 | uint8 MODE_LATERAL_CLOSED_LOOP = 1
3 | uint8 MODE_SPEED_CLOSED_LOOP = 2
4 | uint8 MODE_OPEN_LOOP = 3
5 |
6 | uint8 STATE_KEEP_LANE = 0
7 | uint8 STATE_CHANGE_LANE_P1 = 1
8 | uint8 STATE_CHANGE_LANE_P2 = 2
9 | uint8 STATE_STOP = 3
10 | uint8 STATE_END = 4
11 |
12 |
13 | Header header
14 |
15 | uint8 mode
16 | pnc_msgs/WayPoint[] way_points
17 | pnc_msgs/VehicleCmd open_loop_cmd
18 | float64 speed
19 | uint8 state
20 |
21 | ########## STOP AT DEST ################################
22 | bool stop_at_dest
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/VehicleOtherCmd.msg:
--------------------------------------------------------------------------------
1 |
2 | uint8 MODE_MANUAL = 100
3 | uint8 MODE_AUTO = 101
4 |
5 | Header header
6 |
7 | uint8 turn_light_mode
8 | uint8 turn_light #0:left 1:right 2:both 3:invalid
9 |
10 | uint8 light_mode
11 | uint8 light #front light 0:close 1:near light 2:far light 3:invalid
12 |
13 | uint8 wiper_mode
14 | uint8 wiper #0:wiper close 1:run wiper 2:reserve 3:invalid
15 |
16 | uint8 door_mode
17 | uint8 door #0:no control 1:normal open 2:emergency open 3:reserve
18 |
19 | uint8 trumpet_mode
20 | uint8 trumpet #0:no control 1:open
21 |
22 | uint8 auto_driver_cmd
23 | uint8 estop_cmd
24 |
25 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/VehicleCmd.msg:
--------------------------------------------------------------------------------
1 | uint8 MODE_MANUAL = 100
2 | uint8 MODE_AUTO = 101
3 |
4 | uint8 OFF = 150 # For horn, left_light and right_light
5 | uint8 ON = 151 # For horn, left_light and right_light
6 |
7 | Header header
8 |
9 | uint8 steering_mode
10 | float64 steering_angle # -1.0 ~ 1.0, positive number on the right side
11 | float64 steering_speed # 0.0 ~ 1.0
12 |
13 | uint8 throttle_mode
14 | float64 throttle # 0.0 ~ 1.0
15 | uint8 brake_mode
16 | float64 brake # 0.0 ~ 1.0
17 |
18 | float64 acceleration_request # m/s2
19 | uint8 acceleration_mode
20 |
21 | pnc_msgs/Gear gear
22 | uint8 gear_mode
23 | uint8 horn
24 | uint8 left_light
25 | uint8 right_light
26 |
27 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/DecisionCmd.msg:
--------------------------------------------------------------------------------
1 | uint8 LATERAL_MANEUVER_KEEP_IN_LANE = 0
2 | uint8 LATERAL_MANEUVER_BYPASS_IN_LANE = 1
3 | uint8 LATERAL_MANEUVER_CHANGE_TO_LEFT = 2
4 | uint8 LATERAL_MANEUVER_CHANGE_TO_RIGHT = 3
5 |
6 | uint8 SPEED_MANEUVER_FREE = 0
7 | uint8 SPEED_MANEUVER_FOLLOW = 1
8 | uint8 SPEED_MANEUVER_STOP = 2
9 | uint8 SPEED_MANEUVER_ESTOP = 3
10 |
11 |
12 |
13 | Header header
14 |
15 | uint8 lateral_maneuver
16 | uint8 speed_maneuver
17 | float64 speed_limit
18 | int32 target_lane_id
19 |
20 |
21 | ########## For SPEED_MANEUVER_FOLLOW ###################
22 |
23 | VirtualWall[] virtual_wall
24 |
25 | ########## For LATERAL_MANEUVER_CHANGE_TO_* ############
26 | float64 gap_speed_front
27 | float64 gap_speed_back
28 | float64 gap_distance_front
29 | float64 gap_distance_back
30 |
--------------------------------------------------------------------------------
/src/radar_visualizer/include/radar_visualizer.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-12.
3 | //
4 |
5 | #ifndef RADAR_VISUALIZER_RADAR_VISUALIZER_H
6 | #define RADAR_VISUALIZER_RADAR_VISUALIZER_H
7 |
8 | #include "ros/ros.h"
9 | #include "conti_radar_msgs/conti_Objects.h"
10 | #include "conti_radar_msgs/conti_Object.h"
11 | #include "visualization_msgs/Marker.h"
12 |
13 | class RadarVisualizer
14 | {
15 | private:
16 | ros::NodeHandle node_handle_;
17 | ros::Subscriber recv_objects_sub_;
18 |
19 | ros::Publisher send_visualizer_pub_;
20 |
21 | public:
22 | RadarVisualizer();
23 | ~RadarVisualizer();
24 |
25 |
26 | void init();
27 | void doListening();
28 |
29 | void objectsCallback(const conti_radar_msgs::conti_Objects::ConstPtr &objects);
30 | };
31 |
32 |
33 |
34 | #endif //SENSOR_VISUALIZER_SENSOR_VISUALIZER_H
35 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/VehicleOtherInfo.msg:
--------------------------------------------------------------------------------
1 | uint8 MODE_MANUAL = 70
2 | uint8 MODE_AUTO = 71
3 | uint8 MODE_INTERVENED = 72
4 |
5 | Header header
6 |
7 | uint8 turn_light_status
8 | uint8 door_status
9 | uint8 wiper_status
10 | uint8 trumpet_status
11 | uint8 light_status
12 | uint8 dump_energy_status
13 |
14 | uint8 auto_driver_status #0:auto_driver 1:human intervention 2:udp lost 3:can lost
15 | uint16 vehicle_error_status #contain eight status, each status takes 2 bits vehicle_error/steering_error/gear_error/throttle_error/brake_error/
16 | uint16 transfer_to_upper_cmd #contain eight cmds, each cmd takes 2 bits TBD
17 |
18 | uint8 counter #0~15 cycle counter
19 |
20 | #just for sinotruk_bus
21 | uint8 v2x_link_status
22 | uint8 v2x_light_left_time
23 | uint8 v2x_light_status
24 | float64 v2x_distance_to_stop
25 |
26 |
27 |
28 |
--------------------------------------------------------------------------------
/src/msgs/perception_msgs/msg/Object.msg:
--------------------------------------------------------------------------------
1 | int32 id
2 | int32 age
3 | int32 prediction_age
4 |
5 | geometry_msgs/Point reference_point
6 | geometry_msgs/Point bounding_box_center
7 | geometry_msgs/Point bounding_box_size
8 | geometry_msgs/Point object_box_center
9 | geometry_msgs/Point object_box_size
10 |
11 | float64 object_box_orientation
12 | float64 object_box_orientation_absolute
13 |
14 | geometry_msgs/Point absolute_velocity
15 | geometry_msgs/Point absolute_velocity_sigma
16 | geometry_msgs/Point relative_velocity
17 |
18 | geometry_msgs/Point absolute_acceleration
19 | geometry_msgs/Point relative_acceleration
20 |
21 | geometry_msgs/Point absolute_yaw_rate
22 | geometry_msgs/Point relative_yaw_rate
23 |
24 | int32 classification
25 | int32 classification_age
26 | int32 classification_certainty
27 |
28 | geometry_msgs/Point[] contour_points
29 | geometry_msgs/Point[] contour_points_absolute
30 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/VehicleInfo.msg:
--------------------------------------------------------------------------------
1 | uint8 MODE_MANUAL = 70
2 | uint8 MODE_AUTO = 71
3 | uint8 MODE_INTERVENED = 72
4 |
5 | Header header
6 |
7 | float64 vehicle_speed # m/s
8 | float64 odometer # m
9 |
10 | float64[] wheel_speed # m/s, start from FL, clockwise.
11 | float64[] wheel_odometer # m, start from FL, clockwise.
12 |
13 | float64 wheel_angle_left # degree
14 | float64 wheel_angle_right# degree
15 |
16 | float64 yaw_rate # rad/s
17 | float64 gx # m/s2
18 | float64 gy # m/s2
19 |
20 | uint8 steering_mode
21 | float64 steering_angle # degree
22 |
23 | uint8 throttle_mode
24 | float64 throttle # 0.0 ~ 1.0; -1.0 for unavailable.
25 |
26 | uint8 brake_mode
27 | float64 brake # 0.0 ~ 1.0; -1.0 for unavailable.
28 |
29 | uint8 acceleration_mode
30 | float64 acceleration # m/s2
31 |
32 | uint8 gear_mode
33 | pnc_msgs/Gear gear
34 |
--------------------------------------------------------------------------------
/src/conti_radar/config/byd.yaml:
--------------------------------------------------------------------------------
1 | #longitude offset to vehicle center(center of rear axle)
2 | long_offset_mid: 3.6 #unit: m
3 |
4 | #lateral offset to vehicle center(center of rear axle)
5 | lat_offset_mid: 0.23 #unit: m
6 |
7 | #angle offset to vehicle center(center of rear axle)
8 | angular_deviation_mid: 0.0 #degree
9 |
10 | #longitude offset to vehicle center(center of rear axle)
11 | long_offset_left: 0.0 #unit: m
12 |
13 | #lateral offset to vehicle center(center of rear axle)
14 | lat_offset_left: 0.0 #unit: m
15 |
16 | #longtitude offset to vehicle center(center of rear axle)
17 | angular_deviation_left: 0.0 #degree
18 |
19 | #longitude offset to vehicle center(center of rear axle)
20 | long_offset_right: 3.3 #unit: m
21 |
22 | #lateral offset to vehicle center(center of rear axle)
23 | lat_offset_right: 2.5 #unit: m
24 |
25 | #longtitude offset to vehicle center(center of rear axle)
26 | angular_deviation_right: 0.0 #degree
--------------------------------------------------------------------------------
/src/conti_radar/config/cciv.yaml:
--------------------------------------------------------------------------------
1 | #longitude offset to vehicle center(center of rear axle)
2 | long_offset_mid: 3.6 #unit: m
3 |
4 | #lateral offset to vehicle center(center of rear axle)
5 | lat_offset_mid: 0.23 #unit: m
6 |
7 | #angle offset to vehicle center(center of rear axle)
8 | angular_deviation_mid: 0.0 #degree
9 |
10 | #longitude offset to vehicle center(center of rear axle)
11 | long_offset_left: 0.0 #unit: m
12 |
13 | #lateral offset to vehicle center(center of rear axle)
14 | lat_offset_left: 0.0 #unit: m
15 |
16 | #longtitude offset to vehicle center(center of rear axle)
17 | angular_deviation_left: 0.0 #degree
18 |
19 | #longitude offset to vehicle center(center of rear axle)
20 | long_offset_right: 3.3 #unit: m
21 |
22 | #lateral offset to vehicle center(center of rear axle)
23 | lat_offset_right: 2.5 #unit: m
24 |
25 | #longtitude offset to vehicle center(center of rear axle)
26 | angular_deviation_right: 0.0 #degree
--------------------------------------------------------------------------------
/src/conti_radar/config/cs55.yaml:
--------------------------------------------------------------------------------
1 | #longitude offset to vehicle center(center of rear axle)
2 | long_offset_mid: 3.6 #unit: m
3 |
4 | #lateral offset to vehicle center(center of rear axle)
5 | lat_offset_mid: 0.23 #unit: m
6 |
7 | #angle offset to vehicle center(center of rear axle)
8 | angular_deviation_mid: 0.0 #degree
9 |
10 | #longitude offset to vehicle center(center of rear axle)
11 | long_offset_left: 0.0 #unit: m
12 |
13 | #lateral offset to vehicle center(center of rear axle)
14 | lat_offset_left: 0.0 #unit: m
15 |
16 | #longtitude offset to vehicle center(center of rear axle)
17 | angular_deviation_left: 0.0 #degree
18 |
19 | #longitude offset to vehicle center(center of rear axle)
20 | long_offset_right: 3.3 #unit: m
21 |
22 | #lateral offset to vehicle center(center of rear axle)
23 | lat_offset_right: 2.5 #unit: m
24 |
25 | #longtitude offset to vehicle center(center of rear axle)
26 | angular_deviation_right: 0.0 #degree
--------------------------------------------------------------------------------
/src/conti_radar/config/foton.yaml:
--------------------------------------------------------------------------------
1 | #longitude offset to vehicle center(center of rear axle)
2 | long_offset_mid: 3.6 #unit: m
3 |
4 | #lateral offset to vehicle center(center of rear axle)
5 | lat_offset_mid: 0.23 #unit: m
6 |
7 | #angle offset to vehicle center(center of rear axle)
8 | angular_deviation_mid: 0.0 #degree
9 |
10 | #longitude offset to vehicle center(center of rear axle)
11 | long_offset_left: 0.0 #unit: m
12 |
13 | #lateral offset to vehicle center(center of rear axle)
14 | lat_offset_left: 0.0 #unit: m
15 |
16 | #longtitude offset to vehicle center(center of rear axle)
17 | angular_deviation_left: 0.0 #degree
18 |
19 | #longitude offset to vehicle center(center of rear axle)
20 | long_offset_right: 3.3 #unit: m
21 |
22 | #lateral offset to vehicle center(center of rear axle)
23 | lat_offset_right: 2.5 #unit: m
24 |
25 | #longtitude offset to vehicle center(center of rear axle)
26 | angular_deviation_right: 0.0 #degree
--------------------------------------------------------------------------------
/src/conti_radar/config/sinotruk_c7.yaml:
--------------------------------------------------------------------------------
1 | #longitude offset to vehicle center(center of rear axle)
2 | long_offset_mid: 3.6 #unit: m
3 |
4 | #lateral offset to vehicle center(center of rear axle)
5 | lat_offset_mid: 0.23 #unit: m
6 |
7 | #angle offset to vehicle center(center of rear axle)
8 | angular_deviation_mid: 0.0 #degree
9 |
10 | #longitude offset to vehicle center(center of rear axle)
11 | long_offset_left: 0.0 #unit: m
12 |
13 | #lateral offset to vehicle center(center of rear axle)
14 | lat_offset_left: 0.0 #unit: m
15 |
16 | #longtitude offset to vehicle center(center of rear axle)
17 | angular_deviation_left: 0.0 #degree
18 |
19 | #longitude offset to vehicle center(center of rear axle)
20 | long_offset_right: 3.3 #unit: m
21 |
22 | #lateral offset to vehicle center(center of rear axle)
23 | lat_offset_right: 2.5 #unit: m
24 |
25 | #longtitude offset to vehicle center(center of rear axle)
26 | angular_deviation_right: 0.0 #degree
--------------------------------------------------------------------------------
/src/conti_radar/config/sinotruk_t5g.yaml:
--------------------------------------------------------------------------------
1 | #longitude offset to vehicle center(center of rear axle)
2 | long_offset_mid: 6.0 #unit: m
3 |
4 | #lateral offset to vehicle center(center of rear axle)
5 | lat_offset_mid: 0.0 #unit: m
6 |
7 | #angle offset to vehicle center(center of rear axle)
8 | angular_deviation_mid: 90.0 #degree
9 |
10 | #longitude offset to vehicle center(center of rear axle)
11 | long_offset_left: 6.0 #unit: m
12 |
13 | #lateral offset to vehicle center(center of rear axle)
14 | lat_offset_left: -1.12 #unit: m
15 |
16 | #longtitude offset to vehicle center(center of rear axle)
17 | angular_deviation_left: 165.0 #degree
18 |
19 | #longitude offset to vehicle center(center of rear axle)
20 | long_offset_right: 6.0 #unit: m
21 |
22 | #lateral offset to vehicle center(center of rear axle)
23 | lat_offset_right: 1.12 #unit: m
24 |
25 | #longtitude offset to vehicle center(center of rear axle)
26 | angular_deviation_right: 15.0 #degree
--------------------------------------------------------------------------------
/src/conti_radar/include/conti_radar/object_general_info_60b.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #ifndef CONTI_RADAR_OBJECT_GENERAL_INFO_60B_H
6 | #define CONTI_RADAR_OBJECT_GENERAL_INFO_60B_H
7 |
8 | #include
9 | #include "ICANCmd.h"
10 |
11 | struct GeneralInfo
12 | {
13 | int object_id_;
14 | float object_dist_long_;
15 | float object_dist_lat_;
16 | float object_vre_long_;
17 | float object_vre_lat_;
18 | int object_dyn_prop_;
19 | float object_rcs_;
20 | };
21 |
22 | class ObjectGeneralInfo60B
23 | {
24 | private:
25 | int object_id_;
26 | float object_dist_long_;
27 | float object_dist_lat_;
28 | float object_vre_long_;
29 | float object_vre_lat_;
30 | int object_dyn_prop_;
31 | float object_rcs_;
32 |
33 | public:
34 | ObjectGeneralInfo60B();
35 | void unPackBytes(const CAN_DataFrame& can_frame);
36 | int getObjectID();
37 | float getObjectDistLong();
38 | float getObjectDistLat();
39 | float getObjectVreLong();
40 | float getObjectVreLat();
41 | int getObjectDynProp();
42 | float getObjectRcs();
43 | GeneralInfo getGeneralInfo();
44 | };
45 |
46 | #endif //CONTI_RADAR_OBJECT_GENERAL_INFO_60B_H
47 |
--------------------------------------------------------------------------------
/src/conti_radar/include/conti_radar/object_extended_info_60d.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #ifndef CONTI_RADAR_OBJECT_EXTENDED_INFO_60D_H
6 | #define CONTI_RADAR_OBJECT_EXTENDED_INFO_60D_H
7 |
8 | #include "ICANCmd.h"
9 |
10 |
11 | struct ExtendedInfo
12 | {
13 | int object_id_;
14 | float object_arel_long_;
15 | int object_class_;
16 | float object_arel_lat_;
17 | float object_orientation_angel_;
18 | float object_length_;
19 | float object_width_;
20 | };
21 | class ObjectExtendedInfo60D
22 | {
23 | private:
24 | int object_id_;
25 | float object_arel_long_;
26 | int object_class_;
27 | float object_arel_lat_;
28 | float object_orientation_angel_;
29 | float object_length_;
30 | float object_width_;
31 |
32 | public:
33 | ObjectExtendedInfo60D();
34 | void unPackBytes(const CAN_DataFrame& can_frame);
35 |
36 | int getObjectId();
37 | float getObjectArelLong();
38 | int getObjectClass();
39 | float getObjectArelLat();
40 | float getObjectOrientationAngel();
41 | float getObjectLength();
42 | float getObjectWidth();
43 |
44 | ExtendedInfo getExtendedInfo();
45 | };
46 |
47 |
48 | #endif //CONTI_RADAR_OBJECT_EXTENDED_INFO_60D_H
49 |
--------------------------------------------------------------------------------
/src/conti_radar/include/conti_radar/radar_state_201.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #ifndef CONTI_RADAR_RADAR_STATE_201_H
6 | #define CONTI_RADAR_RADAR_STATE_201_H
7 |
8 | #include "ICANCmd.h"
9 |
10 | struct RadarState
11 | {
12 | int NVMReadStatus;
13 | int NVMWriteStatus;
14 | int MaxDistanceCfg;
15 | int Persistent_Error;
16 | int Interference;
17 | int Temperature_Error;
18 | int Temporary_Error;
19 | int Voltage_Error;
20 | int SensorID;
21 | int SortIndex;
22 | int RadarPower;
23 | int OutputType;
24 | int SendQuality;
25 | int SendExtInfo;
26 | int MotionRxState;
27 | int RCS_Threshold;
28 | };
29 |
30 | class RadarState201
31 | {
32 | private:
33 | int NVMReadStatus;
34 | int NVMWriteStatus;
35 | int MaxDistanceCfg;
36 | int Persistent_Error;
37 | int Interference;
38 | int Temperature_Error;
39 | int Temporary_Error;
40 | int Voltage_Error;
41 | int SensorID;
42 | int SortIndex;
43 | int RadarPower;
44 | int OutputType;
45 | int SendQuality;
46 | int SendExtInfo;
47 | int MotionRxState;
48 | int RCS_Threshold;
49 |
50 | public:
51 | RadarState201();
52 | void unPackBytes(const CAN_DataFrame& can_frame);
53 |
54 | int getMaxDistanceCfg();
55 | int getOutputType();
56 | int getRadarPower();
57 | int getSendQuality();
58 | int getSendExtInfo();
59 | int getErrorState();
60 | int getSensorID();
61 | int getSortIndex();
62 | int getMotionRxState();
63 | int getRCS_Threshold();
64 | };
65 |
66 |
67 | #endif //CONTI_RADAR_RADAR_STATE_201_H
68 |
--------------------------------------------------------------------------------
/src/radar_visualizer/src/radar_visualizer.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-12.
3 | //
4 |
5 | #include "radar_visualizer.h"
6 |
7 |
8 |
9 | RadarVisualizer::RadarVisualizer()
10 | {
11 |
12 | }
13 |
14 |
15 | RadarVisualizer::~RadarVisualizer()
16 | {
17 |
18 | }
19 |
20 |
21 | void RadarVisualizer::init()
22 | {
23 | ROS_INFO("begin to run!");
24 | }
25 |
26 |
27 | void RadarVisualizer::objectsCallback(const conti_radar_msgs::conti_Objects::ConstPtr &msgs)
28 | {
29 | visualization_msgs::Marker marker;
30 | int marker_id_ = 0;
31 | for(size_t i = 0; i < msgs->objects.size(); ++i)
32 | {
33 | conti_radar_msgs::conti_Object obj = msgs->objects[i];
34 | geometry_msgs::Point sz;
35 | sz.x = obj.Object_DistLat;//sz.x = obj.object_box_center.x;
36 | sz.y = obj.Object_DistLong;//sz.y = obj.object_box_center.y;
37 | sz.z = 0;
38 | marker.points.push_back(sz);
39 | }
40 | //ROS_ERROR("$$$$$$$$$$");
41 | marker.header.frame_id = "smartcar";
42 | marker.header.stamp = ros::Time(0);
43 | marker.ns = "objects";
44 | marker.action = visualization_msgs::Marker::ADD;
45 | marker.pose.orientation.w = 1.0;
46 | marker.id = marker_id_++;
47 | marker.lifetime = ros::Duration(0.1);
48 | marker.type = visualization_msgs::Marker::POINTS;
49 | marker.scale.x = 1.5;
50 | marker.scale.y = 1.5;
51 | marker.color.r = 1.0;
52 | marker.color.g = 0.0;
53 | marker.color.a = 1.0;
54 |
55 | send_visualizer_pub_.publish(marker);
56 |
57 | }
58 |
59 |
60 | void RadarVisualizer::doListening()
61 | {
62 | send_visualizer_pub_ = node_handle_.advertise(
63 | "visualization_makers",10);
64 |
65 | recv_objects_sub_ = node_handle_.subscribe(
66 | "/conti_radar_1/objects", 1, &RadarVisualizer::objectsCallback, this);//conti_radar_1/objects
67 |
68 |
69 | ros::spin();
70 |
71 | }
72 |
73 |
74 |
75 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/msg/GNSSInfo.msg:
--------------------------------------------------------------------------------
1 | int32 SOLUTION_STATUS_SOL_COMPUTED = 0
2 | int32 SOLUTION_STATUS_INSUFFICIENT_OBS = 1
3 | int32 SOLUTION_STATUS_NO_CONVERGENCE = 2
4 | int32 SOLUTION_STATUS_SINGULARITY = 3
5 | int32 SOLUTION_STATUS_COV_TRACE = 4
6 | int32 SOLUTION_STATUS_COLD_START = 5
7 | int32 SOLUTION_STATUS_V_H_LIMIT = 6
8 | int32 SOLUTION_STATUS_VARIANCE = 7
9 | int32 SOLUTION_STATUS_INTEGRITY_WARNING = 8
10 | int32 SOLUTION_STATUS_PENDING = 9
11 | int32 SOLUTION_STATUS_INVALID_FIX = 10
12 | int32 SOLUTION_STATUS_UNAUTHORIZED = 11
13 |
14 | int32 POSITION_TYPE_NONE = 0
15 | int32 POSITION_TYPE_FIXEDPOS = 1
16 | int32 POSITION_TYPE_FIXEDHEIGHT = 2
17 | int32 POSITION_TYPE_DOPPLER_VELOCITY = 8
18 | int32 POSITION_TYPE_SINGLE = 16
19 | int32 POSITION_TYPE_PSRDIFF = 17
20 | int32 POSITION_TYPE_WAAS = 18
21 | int32 POSITION_TYPE_PROPAGATED = 19
22 | int32 POSITION_TYPE_OMNISTAR = 20
23 | int32 POSITION_TYPE_L1_FLOAT = 32
24 | int32 POSITION_TYPE_IONOFREE_FLOAT = 33
25 | int32 POSITION_TYPE_NARROW_FLOAT = 34
26 | int32 POSITION_TYPE_L1_INT = 48
27 | int32 POSITION_TYPE_NARROW_INT = 50
28 | int32 POSITION_TYPE_OMNISTAR_HP = 64
29 | int32 POSITION_TYPE_OMNISTAR_XP = 65
30 | int32 POSITION_TYPE_PPP_CONVERGING = 68
31 | int32 POSITION_TYPE_PPP = 69
32 | int32 POSITION_TYPE_OPERATIONAL = 70
33 | int32 POSITION_TYPE_WARNING = 71
34 | int32 POSITION_TYPE_OUT_OF_BOUNDS = 72
35 |
36 | #position and velocity
37 | Header header
38 | int32 sendtime
39 | float64 longitude
40 | float64 latitude
41 | geometry_msgs/Vector3 position
42 | int32 UTMZoneNum
43 | uint8 UTMZoneChar
44 | geometry_msgs/Vector3 attitude
45 | geometry_msgs/Vector3 velocity
46 | geometry_msgs/Vector3 SD
47 | float64 second
48 | int32 SatUseNum
49 | int32 SatInViewNum
50 | float64 vel_latency
51 | int32 solution_status
52 | int32 position_type
53 | string status
54 |
55 | #dual antena angle
56 | geometry_msgs/Vector3 attitude_dual
57 | geometry_msgs/Vector3 SD_angle_dual
58 | float64 base_line_length_dual
59 | int32 solution_status_dual
60 | int32 type_dual
61 | int32 solution_source_dual
62 |
63 |
64 |
65 |
--------------------------------------------------------------------------------
/src/conti_radar/include/conti_radar/object_quality_info_60c.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #ifndef CONTI_RADAR_OBJECT_QUALITY_INFO_60C_H
6 | #define CONTI_RADAR_OBJECT_QUALITY_INFO_60C_H
7 |
8 | #include "ICANCmd.h"
9 |
10 | struct QualityInfo
11 | {
12 | int object_id_;
13 | int object_dist_long_rms_;
14 | int object_vrel_long_rms_;
15 | int object_dist_lat_rms_;
16 | int object_vrel_lat_rms_;
17 | int object_arel_long_rms_;
18 | int object_arel_lat_rms_;
19 | int object_orientation_rms_;
20 | int object_meas_state_;
21 | int object_prob_of_exist_;
22 | };
23 |
24 |
25 | class ObjectQualityInfo60C
26 | {
27 | private:
28 | int object_id_;
29 | int object_dist_long_rms_;
30 | int object_vrel_long_rms_;
31 | int object_dist_lat_rms_;
32 | int object_vrel_lat_rms_;
33 | int object_arel_long_rms_;
34 | int object_arel_lat_rms_;
35 | int object_orientation_rms_;
36 | int object_meas_state_;
37 | int object_prob_of_exist_;
38 |
39 | public:
40 | ObjectQualityInfo60C();
41 | void unPackBytes(const CAN_DataFrame& can_frame);
42 |
43 | int getObjectId();
44 | int getObjectDistLongRms();
45 | int getObjectVrelLongRms();
46 | int getObjectDistLatRms();
47 | int getObjectVrelLatRms();
48 | int getObjectArelLongRms();
49 | int getObjectArelLatRms();
50 | int getOrientationRms();
51 | int getObjectMeasState();
52 | int getObjectProbOfExist();
53 |
54 | QualityInfo getQualityInfo();
55 | };
56 |
57 | /**
58 | * // single value for rms
59 | *--------------------------------------------------
60 | *| parameter | values for | value for
61 | * | orientation [deg] | dist[m], vrel[m/s], arel[m/s²]
62 | *|------------------------------------------------------
63 | *| 0x0
64 | *| 0x1
65 | *| 0x2
66 | *| 0x3
67 | *| 0x4
68 | *| 0x5
69 | *| 0x6
70 | *| 0x7
71 | *| 0x8
72 | *| 0x9
73 | *|
74 | *|
75 | * ***/
76 |
77 |
78 |
79 |
80 | #endif //CONTI_RADAR_OBJECT_QUALITY_INFO_60C_H
81 |
--------------------------------------------------------------------------------
/src/msgs/raw_sensor_msgs/msg/GnssImuInfo.msg:
--------------------------------------------------------------------------------
1 | int32 POSITION_TYPE_NONE = 0
2 | int32 POSITION_TYPE_FIXEDPOS = 1
3 | int32 POSITION_TYPE_FIXEDHEIGHT = 2
4 | int32 POSITION_TYPE_DOPPLER_VELOCITY = 8
5 | int32 POSITION_TYPE_SINGLE = 16
6 | int32 POSITION_TYPE_PSRDIFF = 17
7 | int32 POSITION_TYPE_SBAS = 18
8 | #int32 POSITION_TYPE_WAAS = 18
9 | int32 POSITION_TYPE_PROPAGATED = 19
10 | int32 POSITION_TYPE_OMNISTAR = 20
11 | int32 POSITION_TYPE_L1_FLOAT = 32
12 | int32 POSITION_TYPE_IONOFREE_FLOAT = 33
13 | int32 POSITION_TYPE_NARROW_FLOAT = 34
14 | int32 POSITION_TYPE_L1_INT = 48
15 | int32 POSITION_TYPE_WIDE_INT = 49
16 | int32 POSITION_TYPE_NARROW_INT = 50
17 | int32 POSITION_TYPE_OMNISTAR_HP = 64
18 | int32 POSITION_TYPE_OMNISTAR_XP = 65
19 | #int32 POSITION_TYPE_PPP_CONVERGING = 68
20 | #int32 POSITION_TYPE_PPP = 69
21 | #int32 POSITION_TYPE_OPERATIONAL = 70
22 | #int32 POSITION_TYPE_WARNING = 71
23 | #int32 POSITION_TYPE_OUT_OF_BOUNDS = 72
24 |
25 | Header header
26 |
27 | # position
28 | float64 latitude
29 | float64 longitude
30 | float64 altitude
31 |
32 | float64 utm_east
33 | float64 utm_north
34 |
35 | float32 latitude_std
36 | float32 longitude_std
37 | float32 altitude_std
38 |
39 | # velocity
40 | float64 north_velocity
41 | float64 east_velocity
42 | float64 up_velocity
43 |
44 | float32 north_velocity_std
45 | float32 east_velocity_std
46 | float32 up_velocity_std
47 |
48 | # attitude
49 | float64 roll
50 | float64 pitch
51 | float64 yaw
52 |
53 | float64 x
54 | float64 y
55 | float64 z
56 | float64 w
57 |
58 | float32 roll_std
59 | float32 pitch_std
60 | float32 yaw_std
61 |
62 | #angular velocity
63 | float64 roll_rate
64 | float64 pitch_rate
65 | float64 yaw_rate
66 |
67 | #acceleration
68 | float64 ax
69 | float64 ay
70 | float64 az
71 |
72 | #INS550D status
73 | #initialization status
74 | uint8 init_position
75 | uint8 init_velocity
76 | uint8 init_pitchroll
77 | uint8 init_yaw
78 |
79 | #gps status
80 | int32 gps_status
81 | int32 gps_satellitenum
82 |
83 | #wheel speed status
84 | int32 wheelspeed_status
85 |
86 | #device status
87 | float64 temperature
88 |
--------------------------------------------------------------------------------
/src/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | # toplevel CMakeLists.txt for a catkin workspace
2 | # catkin/cmake/toplevel.cmake
3 |
4 | cmake_minimum_required(VERSION 2.8.3)
5 |
6 | set(CATKIN_TOPLEVEL TRUE)
7 |
8 | # search for catkin within the workspace
9 | set(_cmd "catkin_find_pkg" "catkin" "${CMAKE_SOURCE_DIR}")
10 | execute_process(COMMAND ${_cmd}
11 | RESULT_VARIABLE _res
12 | OUTPUT_VARIABLE _out
13 | ERROR_VARIABLE _err
14 | OUTPUT_STRIP_TRAILING_WHITESPACE
15 | ERROR_STRIP_TRAILING_WHITESPACE
16 | )
17 | if(NOT _res EQUAL 0 AND NOT _res EQUAL 2)
18 | # searching fot catkin resulted in an error
19 | string(REPLACE ";" " " _cmd_str "${_cmd}")
20 | message(FATAL_ERROR "Search for 'catkin' in workspace failed (${_cmd_str}): ${_err}")
21 | endif()
22 |
23 | # include catkin from workspace or via find_package()
24 | if(_res EQUAL 0)
25 | set(catkin_EXTRAS_DIR "${CMAKE_SOURCE_DIR}/${_out}/cmake")
26 | # include all.cmake without add_subdirectory to let it operate in same scope
27 | include(${catkin_EXTRAS_DIR}/all.cmake NO_POLICY_SCOPE)
28 | add_subdirectory("${_out}")
29 |
30 | else()
31 | # use either CMAKE_PREFIX_PATH explicitly passed to CMake as a command line argument
32 | # or CMAKE_PREFIX_PATH from the environment
33 | if(NOT DEFINED CMAKE_PREFIX_PATH)
34 | if(NOT "$ENV{CMAKE_PREFIX_PATH}" STREQUAL "")
35 | string(REPLACE ":" ";" CMAKE_PREFIX_PATH $ENV{CMAKE_PREFIX_PATH})
36 | endif()
37 | endif()
38 |
39 | # list of catkin workspaces
40 | set(catkin_search_path "")
41 | foreach(path ${CMAKE_PREFIX_PATH})
42 | if(EXISTS "${path}/.catkin")
43 | list(FIND catkin_search_path ${path} _index)
44 | if(_index EQUAL -1)
45 | list(APPEND catkin_search_path ${path})
46 | endif()
47 | endif()
48 | endforeach()
49 |
50 | # search for catkin in all workspaces
51 | set(CATKIN_TOPLEVEL_FIND_PACKAGE TRUE)
52 | find_package(catkin QUIET
53 | NO_POLICY_SCOPE
54 | PATHS ${catkin_search_path}
55 | NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH)
56 | unset(CATKIN_TOPLEVEL_FIND_PACKAGE)
57 |
58 | if(NOT catkin_FOUND)
59 | message(FATAL_ERROR "find_package(catkin) failed. catkin was neither found in the workspace nor in the CMAKE_PREFIX_PATH. One reason may be that no ROS setup.sh was sourced before.")
60 | endif()
61 | endif()
62 |
63 | catkin_workspace()
64 |
--------------------------------------------------------------------------------
/src/conti_radar/src/conti_radar/object_general_info_60b.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #include "object_general_info_60b.h"
6 | #include
7 | #include
8 |
9 | ObjectGeneralInfo60B::ObjectGeneralInfo60B()
10 | {
11 | object_id_ = -1;
12 | object_dist_long_ = -1;
13 | object_dist_lat_ = -1;
14 | object_vre_long_ = -1;
15 | object_vre_lat_ = -1;
16 | object_dyn_prop_ = -1;
17 | object_rcs_ = -1;
18 | }
19 |
20 | void ObjectGeneralInfo60B::unPackBytes(const CAN_DataFrame& can_frame)
21 | {
22 | object_id_ = (uint8_t)(can_frame.arryData[0]);
23 | object_dist_long_ = ((uint16_t)(can_frame.arryData[1]<<5) + (uint8_t)((can_frame.arryData[2] & 0xf8)>>3)) * 0.2 - 500;
24 | object_dist_lat_ = ((uint16_t)((can_frame.arryData[2] & 0x07) << 8) + (uint8_t)(can_frame.arryData[3])) * 0.2 - 204.6;
25 | object_vre_long_ = ((uint16_t)(can_frame.arryData[4]<<2) + (uint8_t)((can_frame.arryData[5] & 0xc0)>>6)) * 0.25 - 128;
26 | object_vre_lat_ = ((uint16_t)((can_frame.arryData[5] & 0x3f) << 3) + (uint8_t)((can_frame.arryData[6]&0xe0)>>5)) * 0.25 - 64;
27 | object_dyn_prop_ = (uint8_t)(can_frame.arryData[6] & 0x07);
28 | object_rcs_ = (uint8_t)(can_frame.arryData[7]) * 0.5 -64.0;
29 | }
30 |
31 | int ObjectGeneralInfo60B::getObjectID()
32 | {
33 | return object_id_;
34 | }
35 | float ObjectGeneralInfo60B::getObjectDistLong()
36 | {
37 | return object_dist_long_;
38 | }
39 | float ObjectGeneralInfo60B::getObjectDistLat()
40 | {
41 | return object_dist_lat_;
42 | }
43 | float ObjectGeneralInfo60B::getObjectVreLong()
44 | {
45 | return object_vre_long_;
46 | }
47 | float ObjectGeneralInfo60B::getObjectVreLat()
48 | {
49 | return object_vre_lat_;
50 | }
51 | int ObjectGeneralInfo60B::getObjectDynProp()
52 | {
53 | return object_dyn_prop_;
54 | }
55 | float ObjectGeneralInfo60B::getObjectRcs()
56 | {
57 | return object_rcs_;
58 | }
59 | GeneralInfo ObjectGeneralInfo60B::getGeneralInfo()
60 | {
61 | GeneralInfo general_info_;
62 | general_info_.object_id_ = object_id_;
63 | general_info_.object_dist_long_ = object_dist_long_;
64 | general_info_.object_dist_lat_ = object_dist_lat_;
65 | general_info_.object_vre_lat_ = object_vre_lat_;
66 | general_info_.object_vre_long_ = object_vre_long_;
67 | general_info_.object_dyn_prop_ = object_dyn_prop_;
68 | general_info_.object_rcs_ = object_rcs_;
69 | return general_info_;
70 | }
71 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | hadmap_msgs
4 | 0.0.2
5 | The hadmap_msgs package
6 |
7 |
8 |
9 |
10 | hebei
11 |
12 |
13 |
14 |
15 |
16 | BSD
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 | catkin
43 | roscpp
44 | rospy
45 | std_msgs
46 | message_generation
47 | roscpp
48 | rospy
49 | std_msgs
50 | message_generation
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
--------------------------------------------------------------------------------
/src/radar_visualizer/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | radar_visualizer
4 | 0.0.0
5 | The sensor_visualizer package
6 |
7 |
8 |
9 |
10 | zxkj
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 | catkin
43 | conti_radar_msgs
44 | roscpp
45 | rospy
46 | std_msgs
47 | conti_radar_msgs
48 | roscpp
49 | rospy
50 | std_msgs
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
--------------------------------------------------------------------------------
/src/conti_radar/launch/run_conti_radar.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
--------------------------------------------------------------------------------
/src/conti_radar/src/conti_radar/object_extended_info_60d.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #include "object_extended_info_60d.h"
6 | #include
7 | #include
8 |
9 | ObjectExtendedInfo60D::ObjectExtendedInfo60D()
10 | {
11 | object_id_ = -1;
12 | object_arel_long_ = -1;
13 | object_class_ = -1;
14 | object_arel_lat_ = -1;
15 | object_orientation_angel_ = -1;
16 | object_length_ = -1;
17 | object_width_ = -1;
18 | }
19 |
20 | void ObjectExtendedInfo60D::unPackBytes(const CAN_DataFrame &can_frame)
21 | {
22 | object_id_ = (uint8_t)(can_frame.arryData[0] & 0xff);
23 | object_arel_long_ = ((uint16_t)(can_frame.arryData[1] << 3) + (uint8_t)((can_frame.arryData[2]&0xe0)>>5)) * 0.01 -10;
24 | object_arel_lat_ = ((uint16_t)((can_frame.arryData[2]&0x1f)<<4) + (uint8_t)((can_frame.arryData[3]&0xf0)>>4)) * 0.01 - 2.5;
25 | object_class_ = (uint8_t)(can_frame.arryData[3] & 0x0f);
26 | object_orientation_angel_ = ((uint16_t)(can_frame.arryData[4]<<2) + (uint8_t)((can_frame.arryData[5]&0xc0)>>6))*0.4-180;
27 | object_length_ = ((uint8_t)(can_frame.arryData[6])) * 0.2;
28 | object_width_ = ((uint8_t)(can_frame.arryData[7])) * 0.2;
29 | }
30 |
31 | int ObjectExtendedInfo60D::getObjectId()
32 | {
33 | return object_id_;
34 | }
35 |
36 | float ObjectExtendedInfo60D::getObjectArelLong()
37 | {
38 | return object_arel_long_;
39 | }
40 |
41 | int ObjectExtendedInfo60D::getObjectClass()
42 | {
43 | return object_class_;
44 | }
45 |
46 | float ObjectExtendedInfo60D::getObjectArelLat()
47 | {
48 | return object_arel_lat_;
49 | }
50 |
51 | float ObjectExtendedInfo60D::getObjectOrientationAngel()
52 | {
53 | return object_orientation_angel_;
54 | }
55 |
56 | float ObjectExtendedInfo60D::getObjectLength()
57 | {
58 | return object_length_;
59 | }
60 |
61 | float ObjectExtendedInfo60D::getObjectWidth()
62 | {
63 | return object_width_;
64 | }
65 |
66 | ExtendedInfo ObjectExtendedInfo60D::getExtendedInfo()
67 | {
68 | ExtendedInfo extended_info;
69 | extended_info.object_id_ = object_id_;
70 | extended_info.object_arel_long_ = object_arel_long_;
71 | extended_info.object_arel_lat_ = object_arel_lat_;
72 | extended_info.object_class_ = object_class_;
73 | extended_info.object_orientation_angel_ = object_orientation_angel_;
74 | extended_info.object_length_ = object_length_;
75 | extended_info.object_width_ = object_width_;
76 | return extended_info;
77 | }
78 |
79 |
80 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | pnc_msgs
4 | 0.0.2
5 | The pnc_msgs package
6 |
7 |
8 |
9 |
10 | hebei
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 | catkin
43 | geometry_msgs
44 | message_generation
45 | roscpp
46 | rospy
47 | std_msgs
48 | geometry_msgs
49 | roscpp
50 | rospy
51 | std_msgs
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
--------------------------------------------------------------------------------
/src/msgs/simulator_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | simulator_msgs
4 | 0.0.2
5 | The simulator_msgs package
6 |
7 |
8 |
9 |
10 | hebei
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 | catkin
43 | geometry_msgs
44 | message_generation
45 | roscpp
46 | rospy
47 | std_msgs
48 | geometry_msgs
49 | roscpp
50 | rospy
51 | std_msgs
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
--------------------------------------------------------------------------------
/src/conti_radar/src/conti_radar/radar_state_201.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 | #include "radar_state_201.h"
5 | #include //??
6 |
7 | RadarState201::RadarState201()
8 | {
9 | MaxDistanceCfg = -1;
10 | OutputType = -1;
11 | RadarPower = -1;
12 | SendQuality = -1;
13 | SendExtInfo = -1;
14 | SensorID = -1;
15 | SortIndex = -1;
16 | MotionRxState = -1;
17 | RCS_Threshold = -1;
18 | Persistent_Error = -1;
19 | Interference = -1;
20 | Temperature_Error = -1;
21 | Temporary_Error = -1;
22 | Voltage_Error = -1;
23 | }
24 |
25 | void RadarState201::unPackBytes(const CAN_DataFrame& can_frame)
26 | {
27 | MaxDistanceCfg = ((uint16_t)(can_frame.arryData[1] << 2) + (uint8_t)((can_frame.arryData[2]&0xc0)>>6)) * 2;//why mutl 2
28 | OutputType = (uint8_t)((can_frame.arryData[5]&0x0c)>>2);
29 | RadarPower = (uint8_t)((can_frame.arryData[4]&0x80)>>7);
30 | SendQuality = (uint8_t)((can_frame.arryData[5]&0x10)>>4);
31 | SendExtInfo = (uint8_t)((can_frame.arryData[5]&0x20) >>5);
32 |
33 | Persistent_Error = (uint8_t)((can_frame.arryData[2]&0x20) >>5);
34 | Interference = (uint8_t)((can_frame.arryData[2]&0x10) >>4);
35 | Temperature_Error = (uint8_t)((can_frame.arryData[2]&0x08) >>3);
36 | Temporary_Error = (uint8_t)((can_frame.arryData[2]&0x04) >>2);
37 | Voltage_Error = (uint8_t)((can_frame.arryData[2]&0x02) >>1);
38 | SensorID = (uint8_t)((can_frame.arryData[4]&0x07) >>0);
39 | SortIndex = (uint8_t)((can_frame.arryData[4]&0x70) >>4);
40 | MotionRxState = (uint8_t)((can_frame.arryData[5]&0xC0) >>6);
41 | RCS_Threshold = (uint8_t)((can_frame.arryData[7]&0x1C) >>2);
42 |
43 |
44 | }
45 |
46 | int RadarState201::getMaxDistanceCfg()
47 | {
48 | return MaxDistanceCfg;
49 | }
50 | int RadarState201::getOutputType()
51 | {
52 | return OutputType;
53 | }
54 | int RadarState201::getRadarPower()
55 | {
56 | return RadarPower;
57 | }
58 | int RadarState201::getSendQuality()
59 | {
60 | return SendQuality;
61 | }
62 | int RadarState201::getSendExtInfo()
63 | {
64 | return SendExtInfo;
65 | }
66 |
67 | int RadarState201::getErrorState()
68 | {
69 | return ((Persistent_Error << 4) + (Interference << 3) + (Temperature_Error << 2) + (Temporary_Error << 1) + Voltage_Error);
70 | }
71 | int RadarState201::getSensorID()
72 | {
73 | return SensorID;
74 | }
75 | int RadarState201::getSortIndex()
76 | {
77 | return SortIndex;
78 | }
79 | int RadarState201::getMotionRxState()
80 | {
81 | return MotionRxState;
82 | }
83 | int RadarState201::getRCS_Threshold()
84 | {
85 | return RCS_Threshold;
86 | }
87 |
--------------------------------------------------------------------------------
/src/conti_radar/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | conti_radar
4 | 0.0.0
5 | The conti_radar package
6 |
7 |
8 |
9 |
10 | zxkj
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 | catkin
43 | roscpp
44 | rospy
45 | std_msgs
46 | sensor_msgs
47 | perception_msgs
48 | pnc_msgs
49 | raw_sensor_msgs
50 | roscpp
51 | rospy
52 | std_msgs
53 | sensor_msgs
54 | perception_msgs
55 | pnc_msgs
56 | raw_sensor_msgs
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
--------------------------------------------------------------------------------
/src/conti_radar/include/radar_can.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #ifndef RADAR_CAN_H
6 | #define RADAR_CAN_H
7 |
8 | #include "ICANCmd.h"
9 | #include "ros/ros.h"
10 | #include
11 | #include "pnc_msgs/VehicleInfo.h"
12 | #include "raw_sensor_msgs/GnssImuInfo.h"
13 | #include "pnc_msgs/Gear.h"
14 | #include
15 |
16 | struct CanParameters
17 | {
18 | int can_channel_index;
19 | int can_baudrate;
20 | bool can_is_extern;
21 | bool can_is_remote;
22 | int can_work_mode; //0:normal, 1:listening only
23 | int can_filter_mode; //0:no use, 1:double filter, 2:single filter
24 | uint32_t can_acc_code;
25 | uint32_t can_acc_mask;
26 | int can_status;
27 | };
28 |
29 | class RadarCan
30 | {
31 | public:
32 | RadarCan();
33 | ~RadarCan();
34 |
35 | int doListening();
36 |
37 | // void recvCmdCallBack();
38 | void recvInfoCallback(const ros::TimerEvent&);
39 | void recvVehicleInfoCallback(const pnc_msgs::VehicleInfo::ConstPtr vehicleinfo);
40 | void recvGnssInfoCallback(const raw_sensor_msgs::GnssImuInfo::ConstPtr gnssimuinfo);
41 | void checkMsgCallback(const ros::TimerEvent&);
42 | void sendReqVehiclemsgCallback(const ros::TimerEvent&);
43 | // void quit();
44 | //different radar has different protocol
45 | virtual void setup() = 0;
46 | virtual void transformCanToInfo(std::vector& can_frames, int len) = 0;
47 | virtual bool checkInfo() = 0;
48 |
49 | protected:
50 | //ros interface
51 | ros::Publisher mid_radar_info_pub_;
52 | ros::Publisher left_radar_info_pub_;
53 | ros::Publisher right_radar_info_pub_;
54 | ros::Subscriber vehicle_info_sub_;
55 | ros::Subscriber gnss_info_sub_;
56 |
57 | ros::NodeHandle node_handle_;
58 | ros::Timer recv_info_sub_;
59 | ros::Timer check_msg_;
60 | ros::Timer send_req_vehicle_msg_;
61 |
62 | //can interface
63 | int can_device_handle_;
64 | std::vector can_parameters_;
65 |
66 | //can operate function
67 | int canStart(CanParameters can_parameters);
68 | int canOpen();
69 | int canClose();
70 | int canWrite(CanParameters can_parameters, unsigned int id, unsigned char* buf, unsigned char len);
71 |
72 | int missing_vehicle_info_counter_;
73 | int missing_gnss_info_counter_;
74 | int missing_can_info_counter_;
75 |
76 | int time_sharing_counter_;
77 |
78 | int recv_info_freq_;
79 | int check_msg_freq_;
80 | int send_req_vehicle_msg_freq_;
81 | bool is_recv_info_quit_;
82 |
83 | int max_missing_times_;
84 |
85 | double vehicle_msg_speed_;//provide by speed
86 | double vehicle_msg_yaw_rate_;//provide by gnss_info
87 | int vehicle_msg_motion_status_;
88 |
89 | public:
90 | static bool is_quit_;
91 | };
92 |
93 | #endif //CONTI_RADAR_RADAR_CAN_H
94 |
--------------------------------------------------------------------------------
/src/conti_radar/include/radar_can_conti.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #ifndef RADAR_CAN_CONTI_H
6 | #define RADAR_CAN_CONTI_H
7 |
8 | #include "radar_can.h"
9 | #include
10 |
11 | #include
12 | #include
13 | #include
14 | #include
15 | #include
16 |
17 | #include
18 | #include
19 |
20 | const int OBJECT_LIST_STATUS_MID = 0x0000060A;
21 | const int OBJECT_GENERAL_INFO_MID = 0x0000060B;
22 | const int OBJECT_QUALITY_INFO_MID = 0x0000060C;
23 | const int OBJECT_EXTENDED_INFO_MID = 0x0000060D;
24 |
25 | const int OBJECT_LIST_STATUS_LEFT = 0x0000061A;
26 | const int OBJECT_GENERAL_INFO_LEFT = 0x0000061B;
27 | const int OBJECT_QUALITY_INFO_LEFT = 0x0000061C;
28 | const int OBJECT_EXTENDED_INFO_LEFT = 0x0000061D;
29 |
30 | const int OBJECT_LIST_STATUS_RIGHT = 0x0000062A;
31 | const int OBJECT_GENERAL_INFO_RIGHT = 0x0000062B;
32 | const int OBJECT_QUALITY_INFO_RIGHT = 0x0000062C;
33 | const int OBJECT_EXTENDED_INFO_RIGHT = 0x0000062D;
34 |
35 | const int RADAR_STATE_MID = 0x00000201;
36 | const int RADAR_STATE_LEFT = 0x00000211;
37 | const int RADAR_STATE_RIGHT = 0x00000221;
38 |
39 |
40 | class RadarCan_Conti:public RadarCan
41 | {
42 | public:
43 | RadarCan_Conti();
44 |
45 | virtual bool checkInfo();
46 | virtual void setup();
47 | virtual void transformCanToInfo(std::vector& can_frames, int len);
48 |
49 | void midMessagePub();
50 | void leftMessagePub();
51 | void rightMessagePub();
52 |
53 |
54 | private:
55 |
56 | ObjectListStatus60A object_list_status_;
57 | ObjectGeneralInfo60B object_general_info_;
58 | ObjectQualityInfo60C object_quality_info_;
59 | ObjectExtendedInfo60D object_extended_info_;
60 | RadarState201 radar_state_;
61 |
62 | std::vector general_info_arr_mid_;
63 | std::vector quality_info_arr_mid_;
64 | std::vector extended_info_arr_mid_;
65 |
66 | std::vector general_info_arr_left_;
67 | std::vector quality_info_arr_left_;
68 | std::vector extended_info_arr_left_;
69 |
70 | std::vector general_info_arr_right_;
71 | std::vector quality_info_arr_right_;
72 | std::vector extended_info_arr_right_;
73 |
74 | int object_mid_num_;
75 | int object_left_num_;
76 | int object_right_num_;
77 |
78 | //Used to transform the sensor coordinate system to the vehicle coordinate system.
79 | double long_offset_mid_;
80 | double lat_offset_mid_;
81 | double angular_deviation_mid_;
82 |
83 | double long_offset_left_;
84 | double lat_offset_left_;
85 | double angular_deviation_left_;
86 |
87 | double long_offset_right_;
88 | double lat_offset_right_;
89 | double angular_deviation_right_;
90 |
91 | };
92 |
93 | #endif
94 |
--------------------------------------------------------------------------------
/src/msgs/raw_sensor_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | raw_sensor_msgs
4 | 0.0.0
5 | The raw_sensor_msgs package
6 |
7 |
8 |
9 |
10 | wanghao
11 |
12 |
13 |
14 |
15 |
16 | BSD
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 | catkin
52 | roscpp
53 | rospy
54 | std_msgs
55 | message_generation
56 | roscpp
57 | rospy
58 | std_msgs
59 | message_generation
60 | roscpp
61 | rospy
62 | std_msgs
63 | message_generation
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
--------------------------------------------------------------------------------
/src/conti_radar/src/conti_radar/object_quality_info_60c.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 |
5 | #include "object_quality_info_60c.h"
6 | #include
7 | #include
8 |
9 | ObjectQualityInfo60C::ObjectQualityInfo60C()
10 | {
11 | object_id_ = -1;
12 | object_dist_long_rms_ = -1;
13 | object_vrel_long_rms_ = -1;
14 | object_dist_lat_rms_ = -1;
15 | object_vrel_lat_rms_ = -1;
16 | object_arel_long_rms_ = -1;
17 | object_arel_lat_rms_ = -1;
18 | object_orientation_rms_ = -1;
19 | object_meas_state_ = -1;
20 | object_prob_of_exist_ = -1;
21 | }
22 |
23 | void ObjectQualityInfo60C::unPackBytes(const CAN_DataFrame &can_frame)
24 | {
25 | object_id_ = (uint8_t)(can_frame.arryData[0]);
26 | object_dist_long_rms_ = (uint8_t)((can_frame.arryData[1] & 0xf8) >> 3);
27 | object_dist_lat_rms_ = (uint8_t)((can_frame.arryData[1] & 0x07)<<2 + (can_frame.arryData[2] & 0xc0) >>6);
28 | object_vrel_long_rms_ = (uint8_t)((can_frame.arryData[2] & 0x3e) >> 1);
29 | object_vrel_lat_rms_ = (uint8_t)((can_frame.arryData[2] & 0x01)<< 4 + (can_frame.arryData[3] &0xf0) >> 4);
30 | object_arel_long_rms_ = (uint8_t)((can_frame.arryData[3]&0x0f) + (can_frame.arryData[4]&0x80)>>7);
31 | object_arel_lat_rms_ = (uint8_t)((can_frame.arryData[4]&0x7c)>>2);
32 | object_orientation_rms_ = (uint8_t)((can_frame.arryData[4]&0x03)<<3 + (can_frame.arryData[5]&0xe0)>>5);
33 | object_prob_of_exist_ = (uint8_t)((can_frame.arryData[6]&0xe0)>>5);
34 | object_meas_state_ = (uint8_t)((can_frame.arryData[6]&0x1c)>>2);
35 | }
36 |
37 | int ObjectQualityInfo60C::getObjectId() {
38 | return object_id_;
39 | }
40 |
41 | int ObjectQualityInfo60C::getObjectDistLongRms() {
42 | return object_dist_long_rms_;
43 | }
44 |
45 | int ObjectQualityInfo60C::getObjectDistLatRms() {
46 | return object_dist_lat_rms_;
47 | }
48 |
49 | int ObjectQualityInfo60C::getObjectVrelLongRms() {
50 | return object_vrel_long_rms_;
51 | }
52 |
53 | int ObjectQualityInfo60C::getObjectVrelLatRms() {
54 | return object_vrel_lat_rms_;
55 | }
56 |
57 | int ObjectQualityInfo60C::getObjectArelLongRms() {
58 | return object_arel_lat_rms_;
59 | }
60 |
61 | int ObjectQualityInfo60C::getObjectArelLatRms() {
62 | return object_arel_lat_rms_;
63 | }
64 |
65 | int ObjectQualityInfo60C::getOrientationRms() {
66 | return object_orientation_rms_;
67 | }
68 | int ObjectQualityInfo60C::getObjectProbOfExist() {
69 | return object_prob_of_exist_;
70 | }
71 | int ObjectQualityInfo60C::getObjectMeasState() {
72 | return object_meas_state_;
73 | }
74 |
75 | QualityInfo ObjectQualityInfo60C::getQualityInfo()
76 | {
77 | QualityInfo quality_info;
78 | quality_info.object_id_ = object_id_;
79 | quality_info.object_dist_long_rms_ = object_dist_long_rms_;
80 | quality_info.object_dist_lat_rms_ = object_dist_lat_rms_;
81 | quality_info.object_vrel_long_rms_ = object_vrel_long_rms_;
82 | quality_info.object_vrel_lat_rms_ = object_vrel_lat_rms_;
83 | quality_info.object_arel_long_rms_ = object_arel_long_rms_;
84 | quality_info.object_arel_lat_rms_ = object_arel_lat_rms_;
85 | quality_info.object_orientation_rms_ = object_orientation_rms_;
86 | quality_info.object_prob_of_exist_ = object_prob_of_exist_;
87 | quality_info.object_meas_state_ = object_meas_state_;
88 | return quality_info;
89 | }
90 |
91 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | center_msgs
4 | 0.0.0
5 | The center_msgs package
6 |
7 |
8 |
9 |
10 | xuejiang
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 | catkin
52 | roscpp
53 | rospy
54 | std_msgs
55 | geometry_msgs
56 | message_generation
57 | roscpp
58 | rospy
59 | std_msgs
60 | geometry_msgs
61 | roscpp
62 | rospy
63 | std_msgs
64 | geometry_msgs
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
--------------------------------------------------------------------------------
/src/msgs/perception_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | perception_msgs
4 | 0.0.0
5 | The perception_msgs package
6 |
7 |
8 |
9 |
10 | neocosmical
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 | catkin
52 | geometry_msgs
53 | message_generation
54 | roscpp
55 | rospy
56 | std_msgs
57 | geometry_msgs
58 | roscpp
59 | rospy
60 | std_msgs
61 | geometry_msgs
62 | roscpp
63 | rospy
64 | std_msgs
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
--------------------------------------------------------------------------------
/src/msgs/conti_radar_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | conti_radar_msgs
4 | 0.0.0
5 | The conti_radar_msgs package
6 |
7 |
8 |
9 |
10 | neocosmical
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 | catkin
52 | geometry_msgs
53 | message_generation
54 | roscpp
55 | rospy
56 | std_msgs
57 | geometry_msgs
58 | roscpp
59 | rospy
60 | std_msgs
61 | geometry_msgs
62 | roscpp
63 | rospy
64 | std_msgs
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
--------------------------------------------------------------------------------
/src/msgs/localization_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | localization_msgs
4 | 0.0.0
5 | The localization_msgs package
6 |
7 |
8 |
9 |
10 | hebei
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 | catkin
52 | roscpp
53 | rospy
54 | std_msgs
55 | message_generation
56 | geometry_msgs
57 | roscpp
58 | rospy
59 | std_msgs
60 | message_generation
61 | geometry_msgs
62 | roscpp
63 | rospy
64 | std_msgs
65 | message_generation
66 | geometry_msgs
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
--------------------------------------------------------------------------------
/src/conti_radar/include/conti_radar/ICANCmd.h:
--------------------------------------------------------------------------------
1 | #ifndef _ICANCmd_H_
2 | #define _ICANCmd_H_
3 |
4 | #define TRUE true
5 | #define FALSE false
6 | typedef bool BOOL;
7 | typedef char CHAR;
8 | typedef unsigned char UCHAR;
9 | typedef unsigned char BYTE;
10 | typedef unsigned char *PBYTE;
11 | typedef unsigned short WORD;
12 | typedef unsigned short USHORT;
13 | typedef int INT;
14 | typedef unsigned int UINT;
15 | typedef unsigned int DWORD;
16 | typedef unsigned int *LPDWORD;
17 | typedef unsigned long ULONG;
18 | typedef unsigned long long ULONG64;
19 | typedef void *PVOID;
20 | typedef void *LPVOID;
21 | #define __stdcall
22 | #define PACKED __attribute__( ( packed, aligned(1) ) )
23 |
24 | //接口卡类型定义
25 | #define ACUSB_131B 1
26 | #define ACUSB_132B 2
27 | #define ACPCI_251 3
28 | #define ACPCI_252 4
29 | #define ACPCI_254 5
30 |
31 | #define ACNET_600 6
32 | #define ACNET_622 7
33 | #define LCPCIE_251 8
34 | #define LCPCIE_252 9
35 | #define LCMINIPCIE_251 10
36 | #define LCMINIPCIE_252 11
37 |
38 | //函数调用返回状态值
39 | #define CAN_RESULT_OK 1
40 | #define CAN_RESULT_ERROR 0
41 |
42 | //CAN错误码
43 | enum CAN_ErrorCode
44 | {
45 | CAN_E_NOERROR = 0x0000, // 没有发现错误
46 | CAN_E_OVERFLOW = 0x0001, // CAN控制器内部FIFO溢出
47 | CAN_E_ERRORALARM = 0x0002, // CAN控制器错误报警
48 | CAN_E_PASSIVE = 0x0004, // CAN控制器消极错误
49 | CAN_E_LOSE = 0x0008, // CAN控制器仲裁丢失
50 | CAN_E_BUSERROR = 0x0010, // CAN控制器总线错误
51 |
52 | CAN_E_RCV_BUF = 0x0020, // dll CAN接收BUF出错
53 | CAN_E_ERR_BUF = 0x0040, // dll CAN错误信息BUF出错
54 |
55 | CAN_E_DEVICEOPENED = 0x0100, // 设备已经打开
56 | CAN_E_DEVICEOPEN = 0x0200, // 打开设备错误
57 | CAN_E_DEVICENOTOPEN = 0x0400, // 设备没有打开
58 | CAN_E_BUFFEROVERFLOW = 0x0800, // 缓冲区溢出
59 | CAN_E_DEVICENOTEXIST = 0x1000, // 此设备不存在
60 | CAN_E_LOADKERNELDLL = 0x2000, // 装载动态库失败
61 | CAN_E_CMDFAILED = 0x4000, // 执行命令失败错误码
62 | CAN_E_BUFFERCREATE = 0x8000, // 内存不足
63 | };
64 |
65 | //CAN数据帧类型
66 | typedef struct tagCAN_DataFrame{
67 | UINT uTimeFlag; // 时间标识,对接收帧有效
68 | BYTE nSendType; // 发送帧类型,0-正常发送;1-单次发送;2-自发自收;3-单次自发自收
69 | BYTE bRemoteFlag; // 是否是远程帧
70 | BYTE bExternFlag; // 是否是扩展帧
71 | BYTE nDataLen; // 数据长度
72 | UINT uID; // 报文DI
73 | BYTE arryData[8]; // 报文数据
74 | }PACKED CAN_DataFrame,*PCAN_DataFrame;
75 |
76 | //CAN初始化配置
77 | typedef struct tagCAN_InitConfig{
78 | UCHAR bMode; // 工作模式(0表示正常模式,1表示只听模式)
79 | BYTE nBtrType; // 位定时参数模式(1表示SJA1000,0表示LPC21XX)
80 | BYTE dwBtr[4]; // CAN位定时参数
81 | DWORD dwAccCode; // 验收码
82 | DWORD dwAccMask; // 屏蔽码
83 | BYTE nFilter; // 滤波方式(0表示未设置滤波功能,1表示双滤波,2表示单滤波)
84 | BYTE dwReserved; // 预留字段
85 | }PACKED CAN_InitConfig,*PCAN_InitConfig;
86 |
87 | //CAN设备信息
88 | typedef struct tagCAN_DeviceInformation{
89 | USHORT uHardWareVersion; // 硬件版本
90 | USHORT uFirmWareVersion; // 固件版本
91 | USHORT uDriverVersion; // 驱动版本
92 | USHORT uInterfaceVersion; // 接口库版本
93 | USHORT uInterruptNumber; // 中断号
94 | BYTE bChannelNumber; // 有几路CAN
95 | CHAR szSerialNumber[20]; // 设备序列号
96 | CHAR szHardWareType[40]; // 硬件类型
97 | CHAR szDescription[20]; // 设备描述
98 | } PACKED CAN_DeviceInformation,*PCAN_DeviceInformation;
99 |
100 | //CAN错误信息
101 | typedef struct tagCAN_ErrorInformation{
102 | UINT uErrorCode; // 错误类型
103 | BYTE PassiveErrData[3]; // 消极错误数据
104 | BYTE ArLostErrData; // 仲裁错误数据
105 | } PACKED CAN_ErrorInformation,*PCAN_ErrorInformation;
106 | /**/
107 | // 打开设备
108 | extern "C" DWORD CAN_DeviceOpen(DWORD dwType, DWORD dwIndex,CHAR *pDescription);
109 | // 关闭设备
110 | extern "C" DWORD CAN_DeviceClose(DWORD dwDeviceHandle);
111 |
112 | // 启动CAN
113 | extern "C" DWORD CAN_ChannelStart(DWORD dwDeviceHandle, DWORD dwChannel, PCAN_InitConfig pInitConfig);
114 | // 停止CAN
115 | extern "C" DWORD CAN_ChannelStop(DWORD dwDeviceHandle, DWORD dwChannel);
116 |
117 | // 获取设备信息
118 | extern "C" DWORD CAN_GetDeviceInfo(DWORD dwDeviceHandle, PCAN_DeviceInformation pInfo);
119 | // 获取CAN错误信息
120 | extern "C" DWORD CAN_GetErrorInfo(DWORD dwDeviceHandle, DWORD dwChannel,PCAN_ErrorInformation pErr);
121 |
122 | // 读EEPROM
123 | extern "C" DWORD CAN_ReadEEPROM(DWORD dwDeviceHandle, WORD dwAddr, PBYTE pBuff, WORD nLen);
124 | // 写EEPROM
125 | extern "C" DWORD CAN_WriteEEPROM(DWORD dwDeviceHandle, WORD dwAddr, PBYTE pBuff, WORD nLen);
126 |
127 | // 发送数据
128 | extern "C" ULONG CAN_ChannelSend(DWORD dwDeviceHandle, DWORD dwChannel, PCAN_DataFrame pSend, ULONG nCount);
129 | // 从接收缓冲区中读数据
130 | extern "C" ULONG CAN_ChannelReceive(DWORD dwDeviceHandle, DWORD dwChannel, PCAN_DataFrame pReceive, ULONG nCount, INT nWaitTime=-1);
131 | // 获取接收缓冲区帧数
132 | extern "C" ULONG CAN_GetReceiveCount(DWORD dwDeviceHandle, DWORD dwChannel);
133 | // 清空接收缓冲区
134 | extern "C" DWORD CAN_ClearReceiveBuffer(DWORD dwDeviceHandle, DWORD dwChannel);
135 |
136 | //读寄存器
137 | extern "C" DWORD CAN_ReadRegister(DWORD dwDeviceHandle, DWORD dwChannel,DWORD dwAddr, PBYTE pBuff, WORD nLen);
138 | //写寄存器
139 | extern "C" DWORD CAN_WriteRegister(DWORD dwDeviceHandle, DWORD dwChannel,DWORD dwAddr, PBYTE pBuff, WORD nLen);
140 |
141 | // 获取参数
142 | extern "C" DWORD CAN_GetParam(DWORD dwDeviceHandle, DWORD dwChannel, DWORD dwParamType, PVOID pData);
143 | // 设置参数
144 | extern "C" DWORD CAN_SetParam(DWORD dwDeviceHandle, DWORD dwChannel, DWORD dwParamType, PVOID pData);
145 |
146 |
147 | #endif //_ICANCmd_H_
148 |
--------------------------------------------------------------------------------
/src/msgs/raw_sensor_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(raw_sensor_msgs)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | roscpp
12 | rospy
13 | std_msgs
14 | message_generation
15 | )
16 |
17 | ## System dependencies are found with CMake's conventions
18 | # find_package(Boost REQUIRED COMPONENTS system)
19 |
20 |
21 | ## Uncomment this if the package has a setup.py. This macro ensures
22 | ## modules and global scripts declared therein get installed
23 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
24 | # catkin_python_setup()
25 |
26 | ################################################
27 | ## Declare ROS messages, services and actions ##
28 | ################################################
29 |
30 | ## To declare and build messages, services or actions from within this
31 | ## package, follow these steps:
32 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
33 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
34 | ## * In the file package.xml:
35 | ## * add a build_depend tag for "message_generation"
36 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
37 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
38 | ## but can be declared for certainty nonetheless:
39 | ## * add a run_depend tag for "message_runtime"
40 | ## * In this file (CMakeLists.txt):
41 | ## * add "message_generation" and every package in MSG_DEP_SET to
42 | ## find_package(catkin REQUIRED COMPONENTS ...)
43 | ## * add "message_runtime" and every package in MSG_DEP_SET to
44 | ## catkin_package(CATKIN_DEPENDS ...)
45 | ## * uncomment the add_*_files sections below as needed
46 | ## and list every .msg/.srv/.action file to be processed
47 | ## * uncomment the generate_messages entry below
48 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
49 |
50 | ## Generate messages in the 'msg' folder
51 | add_message_files(
52 | FILES
53 | GnssImuInfo.msg
54 | )
55 |
56 | ## Generate services in the 'srv' folder
57 | # add_service_files(
58 | # FILES
59 | # Service1.srv
60 | # Service2.srv
61 | # )
62 |
63 | ## Generate actions in the 'action' folder
64 | # add_action_files(
65 | # FILES
66 | # Action1.action
67 | # Action2.action
68 | # )
69 |
70 | ## Generate added messages and services with any dependencies listed here
71 | generate_messages(
72 | DEPENDENCIES
73 | std_msgs
74 | )
75 |
76 | ################################################
77 | ## Declare ROS dynamic reconfigure parameters ##
78 | ################################################
79 |
80 | ## To declare and build dynamic reconfigure parameters within this
81 | ## package, follow these steps:
82 | ## * In the file package.xml:
83 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
84 | ## * In this file (CMakeLists.txt):
85 | ## * add "dynamic_reconfigure" to
86 | ## find_package(catkin REQUIRED COMPONENTS ...)
87 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
88 | ## and list every .cfg file to be processed
89 |
90 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
91 | # generate_dynamic_reconfigure_options(
92 | # cfg/DynReconf1.cfg
93 | # cfg/DynReconf2.cfg
94 | # )
95 |
96 | ###################################
97 | ## catkin specific configuration ##
98 | ###################################
99 | ## The catkin_package macro generates cmake config files for your package
100 | ## Declare things to be passed to dependent projects
101 | ## INCLUDE_DIRS: uncomment this if your package contains header files
102 | ## LIBRARIES: libraries you create in this project that dependent projects also need
103 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
104 | ## DEPENDS: system dependencies of this project that dependent projects also need
105 | catkin_package(
106 | # INCLUDE_DIRS include
107 | # LIBRARIES localization_msgs
108 | # CATKIN_DEPENDS roscpp rospy std_msgs
109 | # DEPENDS system_lib
110 | )
111 |
112 | ###########
113 | ## Build ##
114 | ###########
115 |
116 | ## Specify additional locations of header files
117 | ## Your package locations should be listed before other locations
118 | include_directories(
119 | # include
120 | ${catkin_INCLUDE_DIRS}
121 | )
122 |
123 | ## Declare a C++ library
124 | # add_library(${PROJECT_NAME}
125 | # src/${PROJECT_NAME}/localization_msgs.cpp
126 | # )
127 |
128 | ## Add cmake target dependencies of the library
129 | ## as an example, code may need to be generated before libraries
130 | ## either from message generation or dynamic reconfigure
131 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
132 |
133 | ## Declare a C++ executable
134 | ## With catkin_make all packages are built within a single CMake context
135 | ## The recommended prefix ensures that target names across packages don't collide
136 | # add_executable(${PROJECT_NAME}_node src/localization_msgs_node.cpp)
137 |
138 | ## Rename C++ executable without prefix
139 | ## The above recommended prefix causes long target names, the following renames the
140 | ## target back to the shorter version for ease of user use
141 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
142 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
143 |
144 | ## Add cmake target dependencies of the executable
145 | ## same as for the library above
146 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
147 |
148 | ## Specify libraries to link a library or executable target against
149 | # target_link_libraries(${PROJECT_NAME}_node
150 | # ${catkin_LIBRARIES}
151 | # )
152 |
153 | #############
154 | ## Install ##
155 | #############
156 |
157 | # all install targets should use catkin DESTINATION variables
158 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
159 |
160 | ## Mark executable scripts (Python etc.) for installation
161 | ## in contrast to setup.py, you can choose the destination
162 | # install(PROGRAMS
163 | # scripts/my_python_script
164 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
165 | # )
166 |
167 | ## Mark executables and/or libraries for installation
168 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
169 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
170 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
171 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
172 | # )
173 |
174 | ## Mark cpp header files for installation
175 | # install(DIRECTORY include/${PROJECT_NAME}/
176 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
177 | # FILES_MATCHING PATTERN "*.h"
178 | # PATTERN ".svn" EXCLUDE
179 | # )
180 |
181 | ## Mark other files for installation (e.g. launch and bag files, etc.)
182 | # install(FILES
183 | # # myfile1
184 | # # myfile2
185 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
186 | # )
187 |
188 | #############
189 | ## Testing ##
190 | #############
191 |
192 | ## Add gtest based cpp test target and link libraries
193 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_localization_msgs.cpp)
194 | # if(TARGET ${PROJECT_NAME}-test)
195 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
196 | # endif()
197 |
198 | ## Add folders to be run by python nosetests
199 | # catkin_add_nosetests(test)
200 |
--------------------------------------------------------------------------------
/src/msgs/simulator_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(simulator_msgs)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | geometry_msgs
12 | message_generation
13 | roscpp
14 | rospy
15 | std_msgs
16 | )
17 |
18 | ## System dependencies are found with CMake's conventions
19 | # find_package(Boost REQUIRED COMPONENTS system)
20 |
21 |
22 | ## Uncomment this if the package has a setup.py. This macro ensures
23 | ## modules and global scripts declared therein get installed
24 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
25 | # catkin_python_setup()
26 |
27 | ################################################
28 | ## Declare ROS messages, services and actions ##
29 | ################################################
30 |
31 | ## To declare and build messages, services or actions from within this
32 | ## package, follow these steps:
33 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
34 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
35 | ## * In the file package.xml:
36 | ## * add a build_depend tag for "message_generation"
37 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
38 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
39 | ## but can be declared for certainty nonetheless:
40 | ## * add a run_depend tag for "message_runtime"
41 | ## * In this file (CMakeLists.txt):
42 | ## * add "message_generation" and every package in MSG_DEP_SET to
43 | ## find_package(catkin REQUIRED COMPONENTS ...)
44 | ## * add "message_runtime" and every package in MSG_DEP_SET to
45 | ## catkin_package(CATKIN_DEPENDS ...)
46 | ## * uncomment the add_*_files sections below as needed
47 | ## and list every .msg/.srv/.action file to be processed
48 | ## * uncomment the generate_messages entry below
49 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
50 |
51 | ## Generate messages in the 'msg' folder
52 | add_message_files(
53 | FILES
54 | Rate.msg
55 | SetState.msg
56 | )
57 |
58 | ## Generate services in the 'srv' folder
59 | # add_service_files(
60 | # FILES
61 | # Service1.srv
62 | # Service2.srv
63 | # )
64 |
65 | ## Generate actions in the 'action' folder
66 | # add_action_files(
67 | # FILES
68 | # Action1.action
69 | # Action2.action
70 | # )
71 |
72 | ## Generate added messages and services with any dependencies listed here
73 | generate_messages(
74 | DEPENDENCIES
75 | geometry_msgs
76 | std_msgs
77 | )
78 |
79 | ################################################
80 | ## Declare ROS dynamic reconfigure parameters ##
81 | ################################################
82 |
83 | ## To declare and build dynamic reconfigure parameters within this
84 | ## package, follow these steps:
85 | ## * In the file package.xml:
86 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
87 | ## * In this file (CMakeLists.txt):
88 | ## * add "dynamic_reconfigure" to
89 | ## find_package(catkin REQUIRED COMPONENTS ...)
90 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
91 | ## and list every .cfg file to be processed
92 |
93 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
94 | # generate_dynamic_reconfigure_options(
95 | # cfg/DynReconf1.cfg
96 | # cfg/DynReconf2.cfg
97 | # )
98 |
99 | ###################################
100 | ## catkin specific configuration ##
101 | ###################################
102 | ## The catkin_package macro generates cmake config files for your package
103 | ## Declare things to be passed to dependent projects
104 | ## INCLUDE_DIRS: uncomment this if you package contains header files
105 | ## LIBRARIES: libraries you create in this project that dependent projects also need
106 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
107 | ## DEPENDS: system dependencies of this project that dependent projects also need
108 | catkin_package(
109 | # INCLUDE_DIRS include
110 | # LIBRARIES pnc_msgs
111 | # CATKIN_DEPENDS general geometry_msgs message_generation roscpp rospy std_msgs
112 | # DEPENDS system_lib
113 | )
114 |
115 | ###########
116 | ## Build ##
117 | ###########
118 |
119 | ## Specify additional locations of header files
120 | ## Your package locations should be listed before other locations
121 | include_directories(
122 | # include
123 | ${catkin_INCLUDE_DIRS}
124 | )
125 |
126 | ## Declare a C++ library
127 | # add_library(${PROJECT_NAME}
128 | # src/${PROJECT_NAME}/pnc_msgs.cpp
129 | # )
130 |
131 | ## Add cmake target dependencies of the library
132 | ## as an example, code may need to be generated before libraries
133 | ## either from message generation or dynamic reconfigure
134 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
135 |
136 | ## Declare a C++ executable
137 | ## With catkin_make all packages are built within a single CMake context
138 | ## The recommended prefix ensures that target names across packages don't collide
139 | # add_executable(${PROJECT_NAME}_node src/pnc_msgs_node.cpp)
140 |
141 | ## Rename C++ executable without prefix
142 | ## The above recommended prefix causes long target names, the following renames the
143 | ## target back to the shorter version for ease of user use
144 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
145 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
146 |
147 | ## Add cmake target dependencies of the executable
148 | ## same as for the library above
149 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
150 |
151 | ## Specify libraries to link a library or executable target against
152 | # target_link_libraries(${PROJECT_NAME}_node
153 | # ${catkin_LIBRARIES}
154 | # )
155 |
156 | #############
157 | ## Install ##
158 | #############
159 |
160 | # all install targets should use catkin DESTINATION variables
161 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
162 |
163 | ## Mark executable scripts (Python etc.) for installation
164 | ## in contrast to setup.py, you can choose the destination
165 | # install(PROGRAMS
166 | # scripts/my_python_script
167 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
168 | # )
169 |
170 | ## Mark executables and/or libraries for installation
171 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
172 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
173 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
174 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
175 | # )
176 |
177 | ## Mark cpp header files for installation
178 | # install(DIRECTORY include/${PROJECT_NAME}/
179 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
180 | # FILES_MATCHING PATTERN "*.h"
181 | # PATTERN ".svn" EXCLUDE
182 | # )
183 |
184 | ## Mark other files for installation (e.g. launch and bag files, etc.)
185 | # install(FILES
186 | # # myfile1
187 | # # myfile2
188 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
189 | # )
190 |
191 | #############
192 | ## Testing ##
193 | #############
194 |
195 | ## Add gtest based cpp test target and link libraries
196 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_pnc_msgs.cpp)
197 | # if(TARGET ${PROJECT_NAME}-test)
198 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
199 | # endif()
200 |
201 | ## Add folders to be run by python nosetests
202 | # catkin_add_nosetests(test)
203 |
--------------------------------------------------------------------------------
/src/msgs/perception_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(perception_msgs)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | geometry_msgs
12 | message_generation
13 | roscpp
14 | rospy
15 | std_msgs
16 | )
17 |
18 | ## System dependencies are found with CMake's conventions
19 | # find_package(Boost REQUIRED COMPONENTS system)
20 |
21 |
22 | ## Uncomment this if the package has a setup.py. This macro ensures
23 | ## modules and global scripts declared therein get installed
24 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
25 | # catkin_python_setup()
26 |
27 | ################################################
28 | ## Declare ROS messages, services and actions ##
29 | ################################################
30 |
31 | ## To declare and build messages, services or actions from within this
32 | ## package, follow these steps:
33 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
34 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
35 | ## * In the file package.xml:
36 | ## * add a build_depend tag for "message_generation"
37 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
38 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
39 | ## but can be declared for certainty nonetheless:
40 | ## * add a run_depend tag for "message_runtime"
41 | ## * In this file (CMakeLists.txt):
42 | ## * add "message_generation" and every package in MSG_DEP_SET to
43 | ## find_package(catkin REQUIRED COMPONENTS ...)
44 | ## * add "message_runtime" and every package in MSG_DEP_SET to
45 | ## catkin_package(CATKIN_DEPENDS ...)
46 | ## * uncomment the add_*_files sections below as needed
47 | ## and list every .msg/.srv/.action file to be processed
48 | ## * uncomment the generate_messages entry below
49 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
50 |
51 | ## Generate messages in the 'msg' folder
52 | add_message_files(
53 | FILES
54 | Object.msg
55 | Objects.msg
56 | )
57 |
58 | ## Generate services in the 'srv' folder
59 | # add_service_files(
60 | # FILES
61 | # Service1.srv
62 | # Service2.srv
63 | # )
64 |
65 | ## Generate actions in the 'action' folder
66 | # add_action_files(
67 | # FILES
68 | # Action1.action
69 | # Action2.action
70 | # )
71 |
72 | ## Generate added messages and services with any dependencies listed here
73 | generate_messages(
74 | DEPENDENCIES
75 | geometry_msgs
76 | std_msgs
77 | )
78 |
79 | ################################################
80 | ## Declare ROS dynamic reconfigure parameters ##
81 | ################################################
82 |
83 | ## To declare and build dynamic reconfigure parameters within this
84 | ## package, follow these steps:
85 | ## * In the file package.xml:
86 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
87 | ## * In this file (CMakeLists.txt):
88 | ## * add "dynamic_reconfigure" to
89 | ## find_package(catkin REQUIRED COMPONENTS ...)
90 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
91 | ## and list every .cfg file to be processed
92 |
93 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
94 | # generate_dynamic_reconfigure_options(
95 | # cfg/DynReconf1.cfg
96 | # cfg/DynReconf2.cfg
97 | # )
98 |
99 | ###################################
100 | ## catkin specific configuration ##
101 | ###################################
102 | ## The catkin_package macro generates cmake config files for your package
103 | ## Declare things to be passed to dependent projects
104 | ## INCLUDE_DIRS: uncomment this if your package contains header files
105 | ## LIBRARIES: libraries you create in this project that dependent projects also need
106 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
107 | ## DEPENDS: system dependencies of this project that dependent projects also need
108 | catkin_package(
109 | # INCLUDE_DIRS include
110 | # LIBRARIES perception_msgs
111 | # CATKIN_DEPENDS geometry_msgs message_generation roscpp rospy std_msgs
112 | # DEPENDS system_lib
113 | )
114 |
115 | ###########
116 | ## Build ##
117 | ###########
118 |
119 | ## Specify additional locations of header files
120 | ## Your package locations should be listed before other locations
121 | include_directories(
122 | # include
123 | ${catkin_INCLUDE_DIRS}
124 | )
125 |
126 | ## Declare a C++ library
127 | # add_library(${PROJECT_NAME}
128 | # src/${PROJECT_NAME}/perception_msgs.cpp
129 | # )
130 |
131 | ## Add cmake target dependencies of the library
132 | ## as an example, code may need to be generated before libraries
133 | ## either from message generation or dynamic reconfigure
134 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
135 |
136 | ## Declare a C++ executable
137 | ## With catkin_make all packages are built within a single CMake context
138 | ## The recommended prefix ensures that target names across packages don't collide
139 | # add_executable(${PROJECT_NAME}_node src/perception_msgs_node.cpp)
140 |
141 | ## Rename C++ executable without prefix
142 | ## The above recommended prefix causes long target names, the following renames the
143 | ## target back to the shorter version for ease of user use
144 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
145 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
146 |
147 | ## Add cmake target dependencies of the executable
148 | ## same as for the library above
149 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
150 |
151 | ## Specify libraries to link a library or executable target against
152 | # target_link_libraries(${PROJECT_NAME}_node
153 | # ${catkin_LIBRARIES}
154 | # )
155 |
156 | #############
157 | ## Install ##
158 | #############
159 |
160 | # all install targets should use catkin DESTINATION variables
161 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
162 |
163 | ## Mark executable scripts (Python etc.) for installation
164 | ## in contrast to setup.py, you can choose the destination
165 | # install(PROGRAMS
166 | # scripts/my_python_script
167 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
168 | # )
169 |
170 | ## Mark executables and/or libraries for installation
171 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
172 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
173 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
174 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
175 | # )
176 |
177 | ## Mark cpp header files for installation
178 | # install(DIRECTORY include/${PROJECT_NAME}/
179 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
180 | # FILES_MATCHING PATTERN "*.h"
181 | # PATTERN ".svn" EXCLUDE
182 | # )
183 |
184 | ## Mark other files for installation (e.g. launch and bag files, etc.)
185 | # install(FILES
186 | # # myfile1
187 | # # myfile2
188 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
189 | # )
190 |
191 | #############
192 | ## Testing ##
193 | #############
194 |
195 | ## Add gtest based cpp test target and link libraries
196 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_perception_msgs.cpp)
197 | # if(TARGET ${PROJECT_NAME}-test)
198 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
199 | # endif()
200 |
201 | ## Add folders to be run by python nosetests
202 | # catkin_add_nosetests(test)
203 |
--------------------------------------------------------------------------------
/src/msgs/localization_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(localization_msgs)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | roscpp
12 | rospy
13 | std_msgs
14 | message_generation
15 | geometry_msgs
16 | )
17 |
18 | ## System dependencies are found with CMake's conventions
19 | # find_package(Boost REQUIRED COMPONENTS system)
20 |
21 |
22 | ## Uncomment this if the package has a setup.py. This macro ensures
23 | ## modules and global scripts declared therein get installed
24 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
25 | # catkin_python_setup()
26 |
27 | ################################################
28 | ## Declare ROS messages, services and actions ##
29 | ################################################
30 |
31 | ## To declare and build messages, services or actions from within this
32 | ## package, follow these steps:
33 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
34 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
35 | ## * In the file package.xml:
36 | ## * add a build_depend tag for "message_generation"
37 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
38 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
39 | ## but can be declared for certainty nonetheless:
40 | ## * add a run_depend tag for "message_runtime"
41 | ## * In this file (CMakeLists.txt):
42 | ## * add "message_generation" and every package in MSG_DEP_SET to
43 | ## find_package(catkin REQUIRED COMPONENTS ...)
44 | ## * add "message_runtime" and every package in MSG_DEP_SET to
45 | ## catkin_package(CATKIN_DEPENDS ...)
46 | ## * uncomment the add_*_files sections below as needed
47 | ## and list every .msg/.srv/.action file to be processed
48 | ## * uncomment the generate_messages entry below
49 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
50 |
51 | ## Generate messages in the 'msg' folder
52 | add_message_files(
53 | FILES
54 | StopPoint.msg
55 | StopPoints.msg
56 | LidarLoc.msg
57 | )
58 |
59 | ## Generate services in the 'srv' folder
60 | # add_service_files(
61 | # FILES
62 | # Service1.srv
63 | # Service2.srv
64 | # )
65 |
66 | ## Generate actions in the 'action' folder
67 | # add_action_files(
68 | # FILES
69 | # Action1.action
70 | # Action2.action
71 | # )
72 |
73 | ## Generate added messages and services with any dependencies listed here
74 | generate_messages(
75 | DEPENDENCIES
76 | std_msgs
77 | geometry_msgs
78 | )
79 |
80 | ################################################
81 | ## Declare ROS dynamic reconfigure parameters ##
82 | ################################################
83 |
84 | ## To declare and build dynamic reconfigure parameters within this
85 | ## package, follow these steps:
86 | ## * In the file package.xml:
87 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
88 | ## * In this file (CMakeLists.txt):
89 | ## * add "dynamic_reconfigure" to
90 | ## find_package(catkin REQUIRED COMPONENTS ...)
91 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
92 | ## and list every .cfg file to be processed
93 |
94 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
95 | # generate_dynamic_reconfigure_options(
96 | # cfg/DynReconf1.cfg
97 | # cfg/DynReconf2.cfg
98 | # )
99 |
100 | ###################################
101 | ## catkin specific configuration ##
102 | ###################################
103 | ## The catkin_package macro generates cmake config files for your package
104 | ## Declare things to be passed to dependent projects
105 | ## INCLUDE_DIRS: uncomment this if your package contains header files
106 | ## LIBRARIES: libraries you create in this project that dependent projects also need
107 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
108 | ## DEPENDS: system dependencies of this project that dependent projects also need
109 | catkin_package(
110 | # INCLUDE_DIRS include
111 | # LIBRARIES localization_msgs
112 | # CATKIN_DEPENDS roscpp rospy std_msgs
113 | # DEPENDS system_lib
114 | )
115 |
116 | ###########
117 | ## Build ##
118 | ###########
119 |
120 | ## Specify additional locations of header files
121 | ## Your package locations should be listed before other locations
122 | include_directories(
123 | # include
124 | ${catkin_INCLUDE_DIRS}
125 | )
126 |
127 | ## Declare a C++ library
128 | # add_library(${PROJECT_NAME}
129 | # src/${PROJECT_NAME}/localization_msgs.cpp
130 | # )
131 |
132 | ## Add cmake target dependencies of the library
133 | ## as an example, code may need to be generated before libraries
134 | ## either from message generation or dynamic reconfigure
135 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
136 |
137 | ## Declare a C++ executable
138 | ## With catkin_make all packages are built within a single CMake context
139 | ## The recommended prefix ensures that target names across packages don't collide
140 | # add_executable(${PROJECT_NAME}_node src/localization_msgs_node.cpp)
141 |
142 | ## Rename C++ executable without prefix
143 | ## The above recommended prefix causes long target names, the following renames the
144 | ## target back to the shorter version for ease of user use
145 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
146 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
147 |
148 | ## Add cmake target dependencies of the executable
149 | ## same as for the library above
150 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
151 |
152 | ## Specify libraries to link a library or executable target against
153 | # target_link_libraries(${PROJECT_NAME}_node
154 | # ${catkin_LIBRARIES}
155 | # )
156 |
157 | #############
158 | ## Install ##
159 | #############
160 |
161 | # all install targets should use catkin DESTINATION variables
162 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
163 |
164 | ## Mark executable scripts (Python etc.) for installation
165 | ## in contrast to setup.py, you can choose the destination
166 | # install(PROGRAMS
167 | # scripts/my_python_script
168 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
169 | # )
170 |
171 | ## Mark executables and/or libraries for installation
172 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
173 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
174 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
175 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
176 | # )
177 |
178 | ## Mark cpp header files for installation
179 | # install(DIRECTORY include/${PROJECT_NAME}/
180 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
181 | # FILES_MATCHING PATTERN "*.h"
182 | # PATTERN ".svn" EXCLUDE
183 | # )
184 |
185 | ## Mark other files for installation (e.g. launch and bag files, etc.)
186 | # install(FILES
187 | # # myfile1
188 | # # myfile2
189 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
190 | # )
191 |
192 | #############
193 | ## Testing ##
194 | #############
195 |
196 | ## Add gtest based cpp test target and link libraries
197 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_localization_msgs.cpp)
198 | # if(TARGET ${PROJECT_NAME}-test)
199 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
200 | # endif()
201 |
202 | ## Add folders to be run by python nosetests
203 | # catkin_add_nosetests(test)
204 |
--------------------------------------------------------------------------------
/src/radar_visualizer/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(radar_visualizer)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | roscpp
12 | rospy
13 | std_msgs
14 | conti_radar_msgs
15 | )
16 |
17 | ## System dependencies are found with CMake's conventions
18 | # find_package(Boost REQUIRED COMPONENTS system)
19 |
20 |
21 | ## Uncomment this if the package has a setup.py. This macro ensures
22 | ## modules and global scripts declared therein get installed
23 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
24 | # catkin_python_setup()
25 |
26 | ################################################
27 | ## Declare ROS messages, services and actions ##
28 | ################################################
29 |
30 | ## To declare and build messages, services or actions from within this
31 | ## package, follow these steps:
32 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
33 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
34 | ## * In the file package.xml:
35 | ## * add a build_depend tag for "message_generation"
36 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
37 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
38 | ## but can be declared for certainty nonetheless:
39 | ## * add a run_depend tag for "message_runtime"
40 | ## * In this file (CMakeLists.txt):
41 | ## * add "message_generation" and every package in MSG_DEP_SET to
42 | ## find_package(catkin REQUIRED COMPONENTS ...)
43 | ## * add "message_runtime" and every package in MSG_DEP_SET to
44 | ## catkin_package(CATKIN_DEPENDS ...)
45 | ## * uncomment the add_*_files sections below as needed
46 | ## and list every .msg/.srv/.action file to be processed
47 | ## * uncomment the generate_messages entry below
48 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
49 |
50 | ## Generate messages in the 'msg' folder
51 | # add_message_files(
52 | # FILES
53 | # Message1.msg
54 | # Message2.msg
55 | # )
56 |
57 | ## Generate services in the 'srv' folder
58 | # add_service_files(
59 | # FILES
60 | # Service1.srv
61 | # Service2.srv
62 | # )
63 |
64 | ## Generate actions in the 'action' folder
65 | # add_action_files(
66 | # FILES
67 | # Action1.action
68 | # Action2.action
69 | # )
70 |
71 | ## Generate added messages and services with any dependencies listed here
72 | # generate_messages(
73 | # DEPENDENCIES
74 | # perception_msgs# std_msgs
75 | # )
76 |
77 | ################################################
78 | ## Declare ROS dynamic reconfigure parameters ##
79 | ################################################
80 |
81 | ## To declare and build dynamic reconfigure parameters within this
82 | ## package, follow these steps:
83 | ## * In the file package.xml:
84 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
85 | ## * In this file (CMakeLists.txt):
86 | ## * add "dynamic_reconfigure" to
87 | ## find_package(catkin REQUIRED COMPONENTS ...)
88 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
89 | ## and list every .cfg file to be processed
90 |
91 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
92 | # generate_dynamic_reconfigure_options(
93 | # cfg/DynReconf1.cfg
94 | # cfg/DynReconf2.cfg
95 | # )
96 |
97 | ###################################
98 | ## catkin specific configuration ##
99 | ###################################
100 | ## The catkin_package macro generates cmake config files for your package
101 | ## Declare things to be passed to dependent projects
102 | ## INCLUDE_DIRS: uncomment this if you package contains header files
103 | ## LIBRARIES: libraries you create in this project that dependent projects also need
104 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
105 | ## DEPENDS: system dependencies of this project that dependent projects also need
106 | catkin_package(
107 | # INCLUDE_DIRS include
108 | LIBRARIES sensor_visualizer
109 | # CATKIN_DEPENDS perception_msgs roscpp rospy std_msgs
110 | # DEPENDS system_lib
111 | )
112 |
113 | ###########
114 | ## Build ##
115 | ###########
116 |
117 | ## Specify additional locations of header files
118 | ## Your package locations should be listed before other locations
119 | include_directories(
120 | # include
121 | ${catkin_INCLUDE_DIRS}
122 | src/
123 | include/
124 | )
125 |
126 | ## Declare a C++ library
127 | add_library(${PROJECT_NAME}
128 | src/radar_visualizer.cpp
129 | )
130 |
131 | ## Add cmake target dependencies of the library
132 | ## as an example, code may need to be generated before libraries
133 | ## either from message generation or dynamic reconfigure
134 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
135 |
136 | ## Declare a C++ executable
137 | ## With catkin_make all packages are built within a single CMake context
138 | ## The recommended prefix ensures that target names across packages don't collide
139 | add_executable(${PROJECT_NAME}_node tool/radar_visualizer_node.cpp)
140 |
141 | ## Rename C++ executable without prefix
142 | ## The above recommended prefix causes long target names, the following renames the
143 | ## target back to the shorter version for ease of user use
144 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
145 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
146 |
147 | ## Add cmake target dependencies of the executable
148 | ## same as for the library above
149 | add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
150 |
151 | ## Specify libraries to link a library or executable target against
152 | target_link_libraries(${PROJECT_NAME}_node
153 | ${catkin_LIBRARIES}
154 | radar_visualizer
155 | )
156 |
157 | #############
158 | ## Install ##
159 | #############
160 |
161 | # all install targets should use catkin DESTINATION variables
162 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
163 |
164 | ## Mark executable scripts (Python etc.) for installation
165 | ## in contrast to setup.py, you can choose the destination
166 | # install(PROGRAMS
167 | # scripts/my_python_script
168 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
169 | # )
170 |
171 | ## Mark executables and/or libraries for installation
172 | install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
173 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
174 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
175 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
176 | )
177 |
178 | ## Mark cpp header files for installation
179 | # install(DIRECTORY include/${PROJECT_NAME}/
180 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
181 | # FILES_MATCHING PATTERN "*.h"
182 | # PATTERN ".svn" EXCLUDE
183 | # )
184 |
185 | ## Mark other files for installation (e.g. launch and bag files, etc.)
186 | # install(FILES
187 | # # myfile1
188 | # # myfile2
189 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
190 | # )
191 |
192 | #############
193 | ## Testing ##
194 | #############
195 |
196 | ## Add gtest based cpp test target and link libraries
197 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_sensor_visualizer.cpp)
198 | # if(TARGET ${PROJECT_NAME}-test)
199 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
200 | # endif()
201 |
202 | ## Add folders to be run by python nosetests
203 | # catkin_add_nosetests(test)
204 |
--------------------------------------------------------------------------------
/src/msgs/conti_radar_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(conti_radar_msgs)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | geometry_msgs
12 | message_generation
13 | roscpp
14 | rospy
15 | std_msgs
16 | )
17 |
18 | ## System dependencies are found with CMake's conventions
19 | # find_package(Boost REQUIRED COMPONENTS system)
20 |
21 |
22 | ## Uncomment this if the package has a setup.py. This macro ensures
23 | ## modules and global scripts declared therein get installed
24 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
25 | # catkin_python_setup()
26 |
27 | ################################################
28 | ## Declare ROS messages, services and actions ##
29 | ################################################
30 |
31 | ## To declare and build messages, services or actions from within this
32 | ## package, follow these steps:
33 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
34 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
35 | ## * In the file package.xml:
36 | ## * add a build_depend tag for "message_generation"
37 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
38 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
39 | ## but can be declared for certainty nonetheless:
40 | ## * add a run_depend tag for "message_runtime"
41 | ## * In this file (CMakeLists.txt):
42 | ## * add "message_generation" and every package in MSG_DEP_SET to
43 | ## find_package(catkin REQUIRED COMPONENTS ...)
44 | ## * add "message_runtime" and every package in MSG_DEP_SET to
45 | ## catkin_package(CATKIN_DEPENDS ...)
46 | ## * uncomment the add_*_files sections below as needed
47 | ## and list every .msg/.srv/.action file to be processed
48 | ## * uncomment the generate_messages entry below
49 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
50 |
51 | ## Generate messages in the 'msg' folder
52 | add_message_files(
53 | FILES
54 | conti_Object.msg
55 | conti_Objects.msg
56 | )
57 |
58 | ## Generate services in the 'srv' folder
59 | # add_service_files(
60 | # FILES
61 | # Service1.srv
62 | # Service2.srv
63 | # )
64 |
65 | ## Generate actions in the 'action' folder
66 | # add_action_files(
67 | # FILES
68 | # Action1.action
69 | # Action2.action
70 | # )
71 |
72 | ## Generate added messages and services with any dependencies listed here
73 | generate_messages(
74 | DEPENDENCIES
75 | geometry_msgs
76 | std_msgs
77 | )
78 |
79 | ################################################
80 | ## Declare ROS dynamic reconfigure parameters ##
81 | ################################################
82 |
83 | ## To declare and build dynamic reconfigure parameters within this
84 | ## package, follow these steps:
85 | ## * In the file package.xml:
86 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
87 | ## * In this file (CMakeLists.txt):
88 | ## * add "dynamic_reconfigure" to
89 | ## find_package(catkin REQUIRED COMPONENTS ...)
90 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
91 | ## and list every .cfg file to be processed
92 |
93 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
94 | # generate_dynamic_reconfigure_options(
95 | # cfg/DynReconf1.cfg
96 | # cfg/DynReconf2.cfg
97 | # )
98 |
99 | ###################################
100 | ## catkin specific configuration ##
101 | ###################################
102 | ## The catkin_package macro generates cmake config files for your package
103 | ## Declare things to be passed to dependent projects
104 | ## INCLUDE_DIRS: uncomment this if your package contains header files
105 | ## LIBRARIES: libraries you create in this project that dependent projects also need
106 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
107 | ## DEPENDS: system dependencies of this project that dependent projects also need
108 | catkin_package(
109 | # INCLUDE_DIRS include
110 | # LIBRARIES perception_msgs
111 | # CATKIN_DEPENDS geometry_msgs message_generation roscpp rospy std_msgs
112 | # DEPENDS system_lib
113 | )
114 |
115 | ###########
116 | ## Build ##
117 | ###########
118 |
119 | ## Specify additional locations of header files
120 | ## Your package locations should be listed before other locations
121 | include_directories(
122 | # include
123 | ${catkin_INCLUDE_DIRS}
124 | )
125 |
126 | ## Declare a C++ library
127 | # add_library(${PROJECT_NAME}
128 | # src/${PROJECT_NAME}/perception_msgs.cpp
129 | # )
130 |
131 | ## Add cmake target dependencies of the library
132 | ## as an example, code may need to be generated before libraries
133 | ## either from message generation or dynamic reconfigure
134 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
135 |
136 | ## Declare a C++ executable
137 | ## With catkin_make all packages are built within a single CMake context
138 | ## The recommended prefix ensures that target names across packages don't collide
139 | # add_executable(${PROJECT_NAME}_node src/perception_msgs_node.cpp)
140 |
141 | ## Rename C++ executable without prefix
142 | ## The above recommended prefix causes long target names, the following renames the
143 | ## target back to the shorter version for ease of user use
144 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
145 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
146 |
147 | ## Add cmake target dependencies of the executable
148 | ## same as for the library above
149 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
150 |
151 | ## Specify libraries to link a library or executable target against
152 | # target_link_libraries(${PROJECT_NAME}_node
153 | # ${catkin_LIBRARIES}
154 | # )
155 |
156 | #############
157 | ## Install ##
158 | #############
159 |
160 | # all install targets should use catkin DESTINATION variables
161 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
162 |
163 | ## Mark executable scripts (Python etc.) for installation
164 | ## in contrast to setup.py, you can choose the destination
165 | # install(PROGRAMS
166 | # scripts/my_python_script
167 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
168 | # )
169 |
170 | ## Mark executables and/or libraries for installation
171 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
172 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
173 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
174 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
175 | # )
176 |
177 | ## Mark cpp header files for installation
178 | # install(DIRECTORY include/${PROJECT_NAME}/
179 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
180 | # FILES_MATCHING PATTERN "*.h"
181 | # PATTERN ".svn" EXCLUDE
182 | # )
183 |
184 | ## Mark other files for installation (e.g. launch and bag files, etc.)
185 | # install(FILES
186 | # # myfile1
187 | # # myfile2
188 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
189 | # )
190 |
191 | #############
192 | ## Testing ##
193 | #############
194 |
195 | ## Add gtest based cpp test target and link libraries
196 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_perception_msgs.cpp)
197 | # if(TARGET ${PROJECT_NAME}-test)
198 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
199 | # endif()
200 |
201 | ## Add folders to be run by python nosetests
202 | # catkin_add_nosetests(test)
203 |
--------------------------------------------------------------------------------
/src/msgs/center_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(center_msgs)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | geometry_msgs
12 | message_generation
13 | roscpp
14 | rospy
15 | std_msgs
16 | )
17 |
18 | ## System dependencies are found with CMake's conventions
19 | # find_package(Boost REQUIRED COMPONENTS system)
20 |
21 |
22 | ## Uncomment this if the package has a setup.py. This macro ensures
23 | ## modules and global scripts declared therein get installed
24 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
25 | # catkin_python_setup()
26 |
27 | ################################################
28 | ## Declare ROS messages, services and actions ##
29 | ################################################
30 |
31 | ## To declare and build messages, services or actions from within this
32 | ## package, follow these steps:
33 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
34 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
35 | ## * In the file package.xml:
36 | ## * add a build_depend tag for "message_generation"
37 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
38 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
39 | ## but can be declared for certainty nonetheless:
40 | ## * add a run_depend tag for "message_runtime"
41 | ## * In this file (CMakeLists.txt):
42 | ## * add "message_generation" and every package in MSG_DEP_SET to
43 | ## find_package(catkin REQUIRED COMPONENTS ...)
44 | ## * add "message_runtime" and every package in MSG_DEP_SET to
45 | ## catkin_package(CATKIN_DEPENDS ...)
46 | ## * uncomment the add_*_files sections below as needed
47 | ## and list every .msg/.srv/.action file to be processed
48 | ## * uncomment the generate_messages entry below
49 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
50 |
51 | ## Generate messages in the 'msg' folder
52 | add_message_files(
53 | FILES
54 | Ack.msg
55 | GlobalPath.msg
56 | TruckPose.msg
57 | TosTarget.msg
58 | TruckArrived.msg
59 | VehicleTarget.msg
60 | CalibrateSwitch.msg
61 | DestPoint.msg
62 | VehicleStopAccurate.msg
63 | ExternalCenterCmd.msg
64 | PlcStopCmd.msg
65 | )
66 |
67 | ## Generate services in the 'srv' folder
68 | # add_service_files(
69 | # FILES
70 | # Service1.srv
71 | # Service2.srv
72 | # )
73 |
74 | ## Generate actions in the 'action' folder
75 | # add_action_files(
76 | # FILES
77 | # Action1.action
78 | # Action2.action
79 | # )
80 |
81 | ## Generate added messages and services with any dependencies listed here
82 | generate_messages(
83 | DEPENDENCIES
84 | geometry_msgs
85 | std_msgs
86 | )
87 |
88 | ################################################
89 | ## Declare ROS dynamic reconfigure parameters ##
90 | ################################################
91 |
92 | ## To declare and build dynamic reconfigure parameters within this
93 | ## package, follow these steps:
94 | ## * In the file package.xml:
95 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
96 | ## * In this file (CMakeLists.txt):
97 | ## * add "dynamic_reconfigure" to
98 | ## find_package(catkin REQUIRED COMPONENTS ...)
99 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
100 | ## and list every .cfg file to be processed
101 |
102 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
103 | # generate_dynamic_reconfigure_options(
104 | # cfg/DynReconf1.cfg
105 | # cfg/DynReconf2.cfg
106 | # )
107 |
108 | ###################################
109 | ## catkin specific configuration ##
110 | ###################################
111 | ## The catkin_package macro generates cmake config files for your package
112 | ## Declare things to be passed to dependent projects
113 | ## INCLUDE_DIRS: uncomment this if your package contains header files
114 | ## LIBRARIES: libraries you create in this project that dependent projects also need
115 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
116 | ## DEPENDS: system dependencies of this project that dependent projects also need
117 | catkin_package(
118 | # INCLUDE_DIRS include
119 | # LIBRARIES center_msgs
120 | # CATKIN_DEPENDS other_catkin_pkg
121 | # DEPENDS system_lib
122 | )
123 |
124 | ###########
125 | ## Build ##
126 | ###########
127 |
128 | ## Specify additional locations of header files
129 | ## Your package locations should be listed before other locations
130 | include_directories(
131 | # include
132 | ${catkin_INCLUDE_DIRS}
133 | )
134 |
135 | ## Declare a C++ library
136 | # add_library(${PROJECT_NAME}
137 | # src/${PROJECT_NAME}/center_msgs.cpp
138 | # )
139 |
140 | ## Add cmake target dependencies of the library
141 | ## as an example, code may need to be generated before libraries
142 | ## either from message generation or dynamic reconfigure
143 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
144 |
145 | ## Declare a C++ executable
146 | ## With catkin_make all packages are built within a single CMake context
147 | ## The recommended prefix ensures that target names across packages don't collide
148 | # add_executable(${PROJECT_NAME}_node src/center_msgs_node.cpp)
149 |
150 | ## Rename C++ executable without prefix
151 | ## The above recommended prefix causes long target names, the following renames the
152 | ## target back to the shorter version for ease of user use
153 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
154 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
155 |
156 | ## Add cmake target dependencies of the executable
157 | ## same as for the library above
158 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
159 |
160 | ## Specify libraries to link a library or executable target against
161 | # target_link_libraries(${PROJECT_NAME}_node
162 | # ${catkin_LIBRARIES}
163 | # )
164 |
165 | #############
166 | ## Install ##
167 | #############
168 |
169 | # all install targets should use catkin DESTINATION variables
170 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
171 |
172 | ## Mark executable scripts (Python etc.) for installation
173 | ## in contrast to setup.py, you can choose the destination
174 | # install(PROGRAMS
175 | # scripts/my_python_script
176 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
177 | # )
178 |
179 | ## Mark executables and/or libraries for installation
180 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
181 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
182 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
183 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
184 | # )
185 |
186 | ## Mark cpp header files for installation
187 | # install(DIRECTORY include/${PROJECT_NAME}/
188 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
189 | # FILES_MATCHING PATTERN "*.h"
190 | # PATTERN ".svn" EXCLUDE
191 | # )
192 |
193 | ## Mark other files for installation (e.g. launch and bag files, etc.)
194 | # install(FILES
195 | # # myfile1
196 | # # myfile2
197 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
198 | # )
199 |
200 | #############
201 | ## Testing ##
202 | #############
203 |
204 | ## Add gtest based cpp test target and link libraries
205 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_center_msgs.cpp)
206 | # if(TARGET ${PROJECT_NAME}-test)
207 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
208 | # endif()
209 |
210 | ## Add folders to be run by python nosetests
211 | # catkin_add_nosetests(test)
212 |
--------------------------------------------------------------------------------
/src/msgs/pnc_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(pnc_msgs)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | geometry_msgs
12 | message_generation
13 | roscpp
14 | rospy
15 | std_msgs
16 | )
17 |
18 | ## System dependencies are found with CMake's conventions
19 | # find_package(Boost REQUIRED COMPONENTS system)
20 |
21 |
22 | ## Uncomment this if the package has a setup.py. This macro ensures
23 | ## modules and global scripts declared therein get installed
24 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
25 | # catkin_python_setup()
26 |
27 | ################################################
28 | ## Declare ROS messages, services and actions ##
29 | ################################################
30 |
31 | ## To declare and build messages, services or actions from within this
32 | ## package, follow these steps:
33 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
34 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
35 | ## * In the file package.xml:
36 | ## * add a build_depend tag for "message_generation"
37 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
38 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
39 | ## but can be declared for certainty nonetheless:
40 | ## * add a run_depend tag for "message_runtime"
41 | ## * In this file (CMakeLists.txt):
42 | ## * add "message_generation" and every package in MSG_DEP_SET to
43 | ## find_package(catkin REQUIRED COMPONENTS ...)
44 | ## * add "message_runtime" and every package in MSG_DEP_SET to
45 | ## catkin_package(CATKIN_DEPENDS ...)
46 | ## * uncomment the add_*_files sections below as needed
47 | ## and list every .msg/.srv/.action file to be processed
48 | ## * uncomment the generate_messages entry below
49 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
50 |
51 | ## Generate messages in the 'msg' folder
52 | add_message_files(
53 | FILES
54 | Gear.msg
55 | WayPoint.msg
56 | VirtualWall.msg
57 | VehicleCmd.msg
58 | VehicleInfo.msg
59 | PlanningCmd.msg
60 | DecisionCmd.msg
61 | VehicleState.msg
62 | TruckState.msg
63 | GNSSInfo.msg
64 | ForceVehicleCmd.msg
65 | VehicleOtherCmd.msg
66 | VehicleOtherInfo.msg
67 | )
68 |
69 | ## Generate services in the 'srv' folder
70 | # add_service_files(
71 | # FILES
72 | # Service1.srv
73 | # Service2.srv
74 | # )
75 |
76 | ## Generate actions in the 'action' folder
77 | # add_action_files(
78 | # FILES
79 | # Action1.action
80 | # Action2.action
81 | # )
82 |
83 | ## Generate added messages and services with any dependencies listed here
84 | generate_messages(
85 | DEPENDENCIES
86 | geometry_msgs
87 | std_msgs
88 | )
89 |
90 | ################################################
91 | ## Declare ROS dynamic reconfigure parameters ##
92 | ################################################
93 |
94 | ## To declare and build dynamic reconfigure parameters within this
95 | ## package, follow these steps:
96 | ## * In the file package.xml:
97 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
98 | ## * In this file (CMakeLists.txt):
99 | ## * add "dynamic_reconfigure" to
100 | ## find_package(catkin REQUIRED COMPONENTS ...)
101 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
102 | ## and list every .cfg file to be processed
103 |
104 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
105 | # generate_dynamic_reconfigure_options(
106 | # cfg/DynReconf1.cfg
107 | # cfg/DynReconf2.cfg
108 | # )
109 |
110 | ###################################
111 | ## catkin specific configuration ##
112 | ###################################
113 | ## The catkin_package macro generates cmake config files for your package
114 | ## Declare things to be passed to dependent projects
115 | ## INCLUDE_DIRS: uncomment this if you package contains header files
116 | ## LIBRARIES: libraries you create in this project that dependent projects also need
117 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
118 | ## DEPENDS: system dependencies of this project that dependent projects also need
119 | catkin_package(
120 | # INCLUDE_DIRS include
121 | # LIBRARIES pnc_msgs
122 | # CATKIN_DEPENDS general geometry_msgs message_generation roscpp rospy std_msgs
123 | # DEPENDS system_lib
124 | )
125 |
126 | ###########
127 | ## Build ##
128 | ###########
129 |
130 | ## Specify additional locations of header files
131 | ## Your package locations should be listed before other locations
132 | include_directories(
133 | # include
134 | ${catkin_INCLUDE_DIRS}
135 | )
136 |
137 | ## Declare a C++ library
138 | # add_library(${PROJECT_NAME}
139 | # src/${PROJECT_NAME}/pnc_msgs.cpp
140 | # )
141 |
142 | ## Add cmake target dependencies of the library
143 | ## as an example, code may need to be generated before libraries
144 | ## either from message generation or dynamic reconfigure
145 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
146 |
147 | ## Declare a C++ executable
148 | ## With catkin_make all packages are built within a single CMake context
149 | ## The recommended prefix ensures that target names across packages don't collide
150 | # add_executable(${PROJECT_NAME}_node src/pnc_msgs_node.cpp)
151 |
152 | ## Rename C++ executable without prefix
153 | ## The above recommended prefix causes long target names, the following renames the
154 | ## target back to the shorter version for ease of user use
155 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
156 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
157 |
158 | ## Add cmake target dependencies of the executable
159 | ## same as for the library above
160 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
161 |
162 | ## Specify libraries to link a library or executable target against
163 | # target_link_libraries(${PROJECT_NAME}_node
164 | # ${catkin_LIBRARIES}
165 | # )
166 |
167 | #############
168 | ## Install ##
169 | #############
170 |
171 | # all install targets should use catkin DESTINATION variables
172 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
173 |
174 | ## Mark executable scripts (Python etc.) for installation
175 | ## in contrast to setup.py, you can choose the destination
176 | # install(PROGRAMS
177 | # scripts/my_python_script
178 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
179 | # )
180 |
181 | ## Mark executables and/or libraries for installation
182 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
183 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
184 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
185 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
186 | # )
187 |
188 | ## Mark cpp header files for installation
189 | # install(DIRECTORY include/${PROJECT_NAME}/
190 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
191 | # FILES_MATCHING PATTERN "*.h"
192 | # PATTERN ".svn" EXCLUDE
193 | # )
194 |
195 | ## Mark other files for installation (e.g. launch and bag files, etc.)
196 | # install(FILES
197 | # # myfile1
198 | # # myfile2
199 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
200 | # )
201 |
202 | #############
203 | ## Testing ##
204 | #############
205 |
206 | ## Add gtest based cpp test target and link libraries
207 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_pnc_msgs.cpp)
208 | # if(TARGET ${PROJECT_NAME}-test)
209 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
210 | # endif()
211 |
212 | ## Add folders to be run by python nosetests
213 | # catkin_add_nosetests(test)
214 |
--------------------------------------------------------------------------------
/src/msgs/hadmap_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(hadmap_msgs)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | geometry_msgs
12 | message_generation
13 | roscpp
14 | rospy
15 | std_msgs
16 | )
17 |
18 | ## System dependencies are found with CMake's conventions
19 | # find_package(Boost REQUIRED COMPONENTS system)
20 |
21 |
22 | ## Uncomment this if the package has a setup.py. This macro ensures
23 | ## modules and global scripts declared therein get installed
24 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
25 | # catkin_python_setup()
26 |
27 | ################################################
28 | ## Declare ROS messages, services and actions ##
29 | ################################################
30 |
31 | ## To declare and build messages, services or actions from within this
32 | ## package, follow these steps:
33 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
34 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
35 | ## * In the file package.xml:
36 | ## * add a build_depend tag for "message_generation"
37 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
38 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
39 | ## but can be declared for certainty nonetheless:
40 | ## * add a run_depend tag for "message_runtime"
41 | ## * In this file (CMakeLists.txt):
42 | ## * add "message_generation" and every package in MSG_DEP_SET to
43 | ## find_package(catkin REQUIRED COMPONENTS ...)
44 | ## * add "message_runtime" and every package in MSG_DEP_SET to
45 | ## catkin_package(CATKIN_DEPENDS ...)
46 | ## * uncomment the add_*_files sections below as needed
47 | ## and list every .msg/.srv/.action file to be processed
48 | ## * uncomment the generate_messages entry below
49 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
50 |
51 | ## Generate messages in the 'msg' folder
52 | # add_message_files(
53 | # FILES
54 | # Message1.msg
55 | # Message2.msg
56 | # )
57 |
58 | add_message_files(
59 | FILES
60 | LocalMapSection.msg
61 | LocalMapLane.msg
62 | LocalMapPoint.msg
63 | MapLane.msg
64 | MapObject.msg
65 | MapPolyCoeff.msg
66 | MapReferLine.msg
67 | MapSection.msg
68 | MapSplineCoeff.msg
69 | Map.msg
70 | Section.msg
71 | Lane.msg
72 | Point.msg
73 | )
74 |
75 | add_service_files(
76 | FILES
77 | LocalMap.srv
78 | # Service2.srv
79 | )
80 |
81 | ## Generate services in the 'srv' folder
82 | # add_service_files(
83 | # FILES
84 | # Service1.srv
85 | # Service2.srv
86 | # )
87 |
88 | ## Generate actions in the 'action' folder
89 | # add_action_files(
90 | # FILES
91 | # Action1.action
92 | # Action2.action
93 | # )
94 |
95 | ## Generate added messages and services with any dependencies listed here
96 | # generate_messages(
97 | # DEPENDENCIES
98 | # std_msgs
99 | # )
100 |
101 | generate_messages(
102 | DEPENDENCIES
103 | geometry_msgs
104 | std_msgs
105 | )
106 | #generate_messages(
107 | # DEPENDENCIES
108 | # geometry_msgs
109 | # std_msgs
110 | #)
111 |
112 | ################################################
113 | ## Declare ROS dynamic reconfigure parameters ##
114 | ################################################
115 |
116 | ## To declare and build dynamic reconfigure parameters within this
117 | ## package, follow these steps:
118 | ## * In the file package.xml:
119 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
120 | ## * In this file (CMakeLists.txt):
121 | ## * add "dynamic_reconfigure" to
122 | ## find_package(catkin REQUIRED COMPONENTS ...)
123 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
124 | ## and list every .cfg file to be processed
125 |
126 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
127 | # generate_dynamic_reconfigure_options(
128 | # cfg/DynReconf1.cfg
129 | # cfg/DynReconf2.cfg
130 | # )
131 |
132 | ###################################
133 | ## catkin specific configuration ##
134 | ###################################
135 | ## The catkin_package macro generates cmake config files for your package
136 | ## Declare things to be passed to dependent projects
137 | ## INCLUDE_DIRS: uncomment this if you package contains header files
138 | ## LIBRARIES: libraries you create in this project that dependent projects also need
139 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
140 | ## DEPENDS: system dependencies of this project that dependent projects also need
141 | catkin_package(
142 | # INCLUDE_DIRS include
143 | # LIBRARIES hadmap
144 | # CATKIN_DEPENDS roscpp rospy std_msgs
145 | # DEPENDS system_lib
146 | )
147 |
148 | ###########
149 | ## Build ##
150 | ###########
151 |
152 | ## Specify additional locations of header files
153 | ## Your package locations should be listed before other locations
154 | include_directories(
155 | # include
156 | ${catkin_INCLUDE_DIRS}
157 | )
158 |
159 | ## Declare a C++ library
160 | # add_library(${PROJECT_NAME}
161 | # src/${PROJECT_NAME}/hadmap.cpp
162 | # )
163 |
164 | ## Add cmake target dependencies of the library
165 | ## as an example, code may need to be generated before libraries
166 | ## either from message generation or dynamic reconfigure
167 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
168 |
169 | ## Declare a C++ executable
170 | ## With catkin_make all packages are built within a single CMake context
171 | ## The recommended prefix ensures that target names across packages don't collide
172 | # add_executable(${PROJECT_NAME}_node src/hadmap_node.cpp)
173 |
174 | ## Rename C++ executable without prefix
175 | ## The above recommended prefix causes long target names, the following renames the
176 | ## target back to the shorter version for ease of user use
177 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
178 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
179 |
180 | ## Add cmake target dependencies of the executable
181 | ## same as for the library above
182 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
183 |
184 | ## Specify libraries to link a library or executable target against
185 | # target_link_libraries(${PROJECT_NAME}_node
186 | # ${catkin_LIBRARIES}
187 | # )
188 |
189 | #############
190 | ## Install ##
191 | #############
192 |
193 | # all install targets should use catkin DESTINATION variables
194 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
195 |
196 | ## Mark executable scripts (Python etc.) for installation
197 | ## in contrast to setup.py, you can choose the destination
198 | # install(PROGRAMS
199 | # scripts/my_python_script
200 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
201 | # )
202 |
203 | ## Mark executables and/or libraries for installation
204 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
205 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
206 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
207 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
208 | # )
209 |
210 | ## Mark cpp header files for installation
211 | # install(DIRECTORY include/${PROJECT_NAME}/
212 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
213 | # FILES_MATCHING PATTERN "*.h"
214 | # PATTERN ".svn" EXCLUDE
215 | # )
216 |
217 | ## Mark other files for installation (e.g. launch and bag files, etc.)
218 | # install(FILES
219 | # # myfile1
220 | # # myfile2
221 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
222 | # )
223 |
224 | #############
225 | ## Testing ##
226 | #############
227 |
228 | ## Add gtest based cpp test target and link libraries
229 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_hadmap.cpp)
230 | # if(TARGET ${PROJECT_NAME}-test)
231 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
232 | # endif()
233 |
234 | ## Add folders to be run by python nosetests
235 | # catkin_add_nosetests(test)
236 |
--------------------------------------------------------------------------------
/src/conti_radar/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(conti_radar)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | roscpp
12 | rospy
13 | std_msgs
14 | sensor_msgs
15 | perception_msgs
16 | pnc_msgs
17 | raw_sensor_msgs
18 | conti_radar_msgs
19 | )
20 |
21 | ## System dependencies are found with CMake's conventions
22 | # find_package(Boost REQUIRED COMPONENTS system)
23 |
24 |
25 | ## Uncomment this if the package has a setup.py. This macro ensures
26 | ## modules and global scripts declared therein get installed
27 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
28 | # catkin_python_setup()
29 |
30 | ################################################
31 | ## Declare ROS messages, services and actions ##
32 | ################################################
33 |
34 | ## To declare and build messages, services or actions from within this
35 | ## package, follow these steps:
36 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
37 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
38 | ## * In the file package.xml:
39 | ## * add a build_depend tag for "message_generation"
40 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
41 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
42 | ## but can be declared for certainty nonetheless:
43 | ## * add a run_depend tag for "message_runtime"
44 | ## * In this file (CMakeLists.txt):
45 | ## * add "message_generation" and every package in MSG_DEP_SET to
46 | ## find_package(catkin REQUIRED COMPONENTS ...)
47 | ## * add "message_runtime" and every package in MSG_DEP_SET to
48 | ## catkin_package(CATKIN_DEPENDS ...)
49 | ## * uncomment the add_*_files sections below as needed
50 | ## and list every .msg/.srv/.action file to be processed
51 | ## * uncomment the generate_messages entry below
52 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
53 |
54 | ## Generate messages in the 'msg' folder
55 | # add_message_files(
56 | # FILES
57 | # Message1.msg
58 | # Message2.msg
59 | # )
60 |
61 | ## Generate services in the 'srv' folder
62 | # add_service_files(
63 | # FILES
64 | # Service1.srv
65 | # Service2.srv
66 | # )
67 |
68 | ## Generate actions in the 'action' folder
69 | # add_action_files(
70 | # FILES
71 | # Action1.action
72 | # Action2.action
73 | # )
74 |
75 | ## Generate added messages and services with any dependencies listed here
76 | # generate_messages(
77 | # DEPENDENCIES
78 | # std_msgs
79 | # )
80 |
81 | ################################################
82 | ## Declare ROS dynamic reconfigure parameters ##
83 | ################################################
84 |
85 | ## To declare and build dynamic reconfigure parameters within this
86 | ## package, follow these steps:
87 | ## * In the file package.xml:
88 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
89 | ## * In this file (CMakeLists.txt):
90 | ## * add "dynamic_reconfigure" to
91 | ## find_package(catkin REQUIRED COMPONENTS ...)
92 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
93 | ## and list every .cfg file to be processed
94 |
95 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
96 | # generate_dynamic_reconfigure_options(
97 | # cfg/DynReconf1.cfg
98 | # cfg/DynReconf2.cfg
99 | # )
100 |
101 | ###################################
102 | ## catkin specific configuration ##
103 | ###################################
104 | ## The catkin_package macro generates cmake config files for your package
105 | ## Declare things to be passed to dependent projects
106 | ## INCLUDE_DIRS: uncomment this if you package contains header files
107 | ## LIBRARIES: libraries you create in this project that dependent projects also need
108 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
109 | ## DEPENDS: system dependencies of this project that dependent projects also need
110 | catkin_package(
111 | INCLUDE_DIRS include
112 | LIBRARIES
113 | CATKIN_DEPENDS #roscpp rospy std_msgs
114 | # DEPENDS system_lib
115 | )
116 |
117 | ###########
118 | ## Build ##
119 | ###########
120 |
121 | ## Specify additional locations of header files
122 | ## Your package locations should be listed before other locations
123 | include_directories(
124 | # include
125 | include/conti_radar
126 | include
127 | ${catkin_INCLUDE_DIRS}
128 | )
129 |
130 | ## Declare a C++ library
131 | add_library(${PROJECT_NAME}
132 | src/radar_can.cpp
133 | src/radar_can_conti.cpp
134 | )
135 |
136 |
137 | find_library(CanCmd_LIBRARIES
138 | CanCmd
139 | PATHS ./lib/can)
140 |
141 | message(STATUS ${CanCmd_LIBRARIES})
142 |
143 | target_link_libraries(${PROJECT_NAME} conti_radar_lib ${CanCmd_LIBRARIES})
144 |
145 | add_subdirectory(src/conti_radar)
146 |
147 | add_executable(conti_radar_node tool/conti_radar_node.cpp)
148 | target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES} ${PROJECT_NAME} conti_radar_lib ${CanCmd_LIBRARIES})
149 |
150 | install(FILES ${CanCmd_LIBRARIES}
151 | DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
152 |
153 | install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
154 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
155 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
156 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
157 | ## Add cmake target dependencies of the library
158 | ## as an example, code may need to be generated before libraries
159 | ## either from message generation or dynamic reconfigure
160 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
161 |
162 | ## Declare a C++ executable
163 | ## With catkin_make all packages are built within a single CMake context
164 | ## The recommended prefix ensures that target names across packages don't collide
165 | # add_executable(${PROJECT_NAME}_node src/conti_radar_node.cpp)
166 |
167 | ## Rename C++ executable without prefix
168 | ## The above recommended prefix causes long target names, the following renames the
169 | ## target back to the shorter version for ease of user use
170 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
171 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
172 |
173 | ## Add cmake target dependencies of the executable
174 | ## same as for the library above
175 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
176 |
177 | ## Specify libraries to link a library or executable target against
178 | # target_link_libraries(${PROJECT_NAME}_node
179 | # ${catkin_LIBRARIES}
180 | # )
181 |
182 | #############
183 | ## Install ##
184 | #############
185 |
186 | # all install targets should use catkin DESTINATION variables
187 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
188 |
189 | ## Mark executable scripts (Python etc.) for installation
190 | ## in contrast to setup.py, you can choose the destination
191 | # install(PROGRAMS
192 | # scripts/my_python_script
193 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
194 | # )
195 |
196 | ## Mark executables and/or libraries for installation
197 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
198 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
199 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
200 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
201 | # )
202 |
203 | ## Mark cpp header files for installation
204 | # install(DIRECTORY include/${PROJECT_NAME}/
205 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
206 | # FILES_MATCHING PATTERN "*.h"
207 | # PATTERN ".svn" EXCLUDE
208 | # )
209 |
210 | ## Mark other files for installation (e.g. launch and bag files, etc.)
211 | install(
212 | DIRECTORY launch/
213 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
214 | FILES_MATCHING PATTERN "*.launch"
215 | )
216 |
217 | install(
218 | DIRECTORY config/
219 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config
220 | FILES_MATCHING PATTERN "*.yaml"
221 | )
222 |
223 | #############
224 | ## Testing ##
225 | #############
226 |
227 | ## Add gtest based cpp test target and link libraries
228 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_conti_radar.cpp)
229 | # if(TARGET ${PROJECT_NAME}-test)
230 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
231 | # endif()
232 |
233 | ## Add folders to be run by python nosetests
234 | # catkin_add_nosetests(test)
235 |
--------------------------------------------------------------------------------
/src/conti_radar/src/radar_can.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 | #include "radar_can.h"
5 | #include
6 | #include
7 | #include
8 | #include
9 |
10 |
11 | bool RadarCan::is_quit_ = false;
12 |
13 | RadarCan::RadarCan()
14 | {
15 | is_recv_info_quit_ = false;
16 | missing_can_info_counter_ = 0;
17 |
18 | canOpen();
19 | }
20 |
21 | RadarCan::~RadarCan()
22 | {
23 | mid_radar_info_pub_.shutdown();
24 | left_radar_info_pub_.shutdown();
25 | right_radar_info_pub_.shutdown();
26 | canClose();
27 |
28 | ros::shutdown();
29 | }
30 |
31 | void RadarCan::recvInfoCallback(const ros::TimerEvent&)
32 | {
33 | CAN_DataFrame buf[100]; // data buffer
34 | std::vector recs; // CAN data frame struct, is related to recv_info_freq_
35 | CAN_ErrorInformation err_info;
36 |
37 | for(size_t i = 0; i < can_parameters_.size(); ++i)
38 | {
39 | int rec_len = 0;
40 | if ((rec_len = CAN_ChannelReceive(can_device_handle_, can_parameters_[i].can_channel_index, buf,
41 | 100, -1)) > 0)
42 | {
43 | missing_can_info_counter_ = 0;
44 | CAN_ClearReceiveBuffer(can_device_handle_, 0);
45 | for(int i = 0; i < rec_len; i++)
46 | {
47 | recs.emplace_back(buf[i]);
48 | }
49 | ROS_INFO("I recv %d CAN frames from radar",rec_len);
50 | transformCanToInfo(recs,rec_len);
51 | }
52 | }
53 | }
54 |
55 |
56 | void RadarCan::recvVehicleInfoCallback(const pnc_msgs::VehicleInfo::ConstPtr vehicleinfo)
57 | {
58 | vehicle_msg_speed_ = vehicleinfo->vehicle_speed;
59 | switch (vehicleinfo->gear.value)
60 | {
61 | case pnc_msgs::Gear::GEAR_P :
62 | case pnc_msgs::Gear::GEAR_N : vehicle_msg_motion_status_ = 0; break;
63 | case pnc_msgs::Gear::GEAR_D : vehicle_msg_motion_status_ = 1; break;
64 | case pnc_msgs::Gear::GEAR_R : vehicle_msg_motion_status_ = 2; break;
65 | default:vehicle_msg_motion_status_ = 0; break;
66 | }
67 |
68 | missing_vehicle_info_counter_ = 0;
69 | }
70 |
71 |
72 | void RadarCan::recvGnssInfoCallback(const raw_sensor_msgs::GnssImuInfo::ConstPtr gnssimuinfo)
73 | {
74 | vehicle_msg_yaw_rate_ = gnssimuinfo->yaw_rate;
75 | missing_gnss_info_counter_ = 0;
76 | }
77 |
78 | //void RadarCan::quit()
79 | //{
80 | // mid_radar_info_pub_.shutdown();
81 | // left_radar_info_pub_.shutdown();
82 | // right_radar_info_pub_.shutdown();
83 | // canClose();
84 | //
85 | // ros::shutdown();
86 | //}
87 |
88 |
89 | void RadarCan::checkMsgCallback(const ros::TimerEvent&)
90 | {
91 | ++missing_can_info_counter_;
92 | ++missing_gnss_info_counter_;
93 | ++missing_vehicle_info_counter_;
94 |
95 | if (missing_can_info_counter_ > 10)
96 | ROS_ERROR("can't receive radar msgs!");
97 |
98 | if (missing_vehicle_info_counter_ > 10)
99 | ROS_ERROR("can't recevie vehicle_info msgs!");
100 |
101 | if (missing_gnss_info_counter_ > 10)
102 | ROS_ERROR("can't receive gnss_imu_info msgs!");
103 |
104 | // signal(SIGINT,&RadarCan::quit);
105 | }
106 |
107 | void RadarCan::sendReqVehiclemsgCallback(const ros::TimerEvent&)
108 | {
109 | CAN_DataFrame send[2];
110 |
111 | if(time_sharing_counter_ % 3 == 0)
112 | {
113 | send[0].uID = 0x300;
114 | send[1].uID = 0x301;
115 | }
116 | else if (time_sharing_counter_ % 3 == 1)
117 | {
118 | send[0].uID = 0x310;
119 | send[1].uID = 0x311;
120 | }
121 | else if (time_sharing_counter_ % 3 == 2)
122 | {
123 | send[0].uID = 0x320;
124 | send[1].uID = 0x321;
125 | }
126 |
127 | send[0].bRemoteFlag = 0; // 0-数据帧;1-远程帧
128 | send[0].bExternFlag = 0; // 0-标准帧;1-扩展帧
129 | send[0].nDataLen = 2;
130 | send[0].nSendType = 0; // 0-正常发送;1-单次发送;2-自发自收;3-单次自发自收
131 | send[0].arryData[0] = (uint8_t)(((((uint16_t)(vehicle_msg_speed_ / 3.6 / 0.02)) >> 8) & 0x1F) + (vehicle_msg_motion_status_ << 6));
132 | send[0].arryData[1] = (uint8_t)(((uint16_t)(vehicle_msg_speed_ / 3.6 / 0.02)) & 0x00FF);
133 | while(CAN_ChannelSend(can_device_handle_, 0, &send[0] , 1) == 0);
134 |
135 | send[1].bRemoteFlag = 0; // 0-数据帧;1-远程帧
136 | send[1].bExternFlag = 0; // 0-标准帧;1-扩展帧
137 | send[1].nDataLen = 2;
138 | send[1].nSendType = 0; // 0-正常发送;1-单次发送;2-自发自收;3-单次自发自收
139 | send[1].arryData[0] = (uint8_t)((((uint16_t)(vehicle_msg_yaw_rate_ / 0.01 + 32768)) & 0xFF00) >> 8);
140 | send[1].arryData[1] = (uint8_t)(((uint16_t)(vehicle_msg_yaw_rate_ / 0.01 + 32768)) & 0x00FF);
141 | while(CAN_ChannelSend(can_device_handle_, 0, &send[1] , 1) == 0);
142 |
143 |
144 | ++time_sharing_counter_;
145 | }
146 |
147 |
148 |
149 |
150 | int RadarCan::doListening()
151 | {
152 | if(can_device_handle_ > 0)
153 | {
154 | for(size_t i = 0; i < can_parameters_.size(); ++i)
155 | {
156 | can_parameters_[i].can_status = canStart(can_parameters_[i]);
157 | }
158 |
159 | ROS_INFO("begin to listen!");
160 |
161 | vehicle_info_sub_ = node_handle_.subscribe(
162 | "pnc_msgs/vehicle_info", 1, &RadarCan::recvVehicleInfoCallback, this);
163 | gnss_info_sub_ = node_handle_.subscribe(
164 | "/trunk_info/gnss_ins", 1, &RadarCan::recvGnssInfoCallback, this);
165 |
166 |
167 | left_radar_info_pub_ = node_handle_.advertise(
168 | "/conti_radar_0/objects", 1);//conti_radar_left
169 | mid_radar_info_pub_ = node_handle_.advertise(
170 | "/conti_radar_1/objects", 1);//conti_radar_mid
171 | right_radar_info_pub_ = node_handle_.advertise(
172 | "/conti_radar_2/objects", 1);//conti_radar_right
173 |
174 | recv_info_sub_ = node_handle_.createTimer(
175 | ros::Duration(1.0 / recv_info_freq_), &RadarCan::recvInfoCallback, this, false, true);
176 | check_msg_ = node_handle_.createTimer(
177 | ros::Duration(1.0 / check_msg_freq_), &RadarCan::checkMsgCallback, this, false, true);
178 | send_req_vehicle_msg_ = node_handle_.createTimer(
179 | ros::Duration(1.0 / send_req_vehicle_msg_freq_), &RadarCan::sendReqVehiclemsgCallback, this, false, true);
180 | ros::spin();
181 |
182 | ROS_INFO("stop to listen!");
183 | }
184 | }
185 |
186 |
187 |
188 | int RadarCan::canOpen()
189 | {
190 | if ((can_device_handle_ = CAN_DeviceOpen(LCMINIPCIE_252, 0, 0)) == 0) //LCMINIPCIE_252 ACUSB_132B
191 | {
192 | ROS_ERROR("open device error.");
193 | return -1;
194 | }
195 | ROS_INFO("open device ok.");
196 | return 0;
197 | }
198 |
199 | int RadarCan::canStart(CanParameters can_parameters)
200 | {
201 | CAN_InitConfig can_init_config;
202 |
203 | can_init_config.dwAccCode = can_parameters.can_acc_code;
204 | can_init_config.dwAccMask = can_parameters.can_acc_mask;
205 | can_init_config.nFilter = can_parameters.can_filter_mode; //滤波方式
206 | can_init_config.bMode = can_parameters.can_work_mode; //工作模式
207 | can_init_config.nBtrType = 1; //定位时参数模式(1表示SJA1000, O表示LPC21XX)
208 |
209 | switch (can_parameters.can_baudrate)
210 | {
211 | case 250:
212 | {
213 | can_init_config.dwBtr[0] = 0x01; //BTR0 0014-1M 0016-800K 001C-500K 001C-250K 031C-12K
214 | can_init_config.dwBtr[1] = 0x1c; //BTR1 041C-100K
215 |
216 | break;
217 | }
218 | case 500:
219 | {
220 | can_init_config.dwBtr[0] = 0x00;
221 | can_init_config.dwBtr[1] = 0x1c;
222 |
223 | break;
224 | }
225 | default:
226 | break;
227 | }
228 | can_init_config.dwBtr[2] = 0;
229 | can_init_config.dwBtr[3] = 0;
230 |
231 | if(CAN_RESULT_OK != CAN_ChannelStart(can_device_handle_, can_parameters.can_channel_index, &can_init_config))
232 | {
233 | ROS_ERROR("start CAN %d error!", can_parameters.can_channel_index);
234 | return -1;
235 | }
236 |
237 | ROS_INFO("start CAN %d success!", can_parameters.can_channel_index );
238 | return 0;
239 | }
240 |
241 | int RadarCan::canClose()
242 | {
243 | for(size_t i = 0; i < can_parameters_.size(); ++i)
244 | {
245 | if(can_parameters_[i].can_status == 0)
246 | {
247 | CAN_ChannelStop(can_device_handle_, can_parameters_[i].can_channel_index);
248 | ROS_INFO("close can %d ok!", can_parameters_[i].can_channel_index);
249 | }
250 | }
251 | if(can_device_handle_ > 0)
252 | {
253 | CAN_DeviceClose(can_device_handle_);
254 | ROS_INFO("close device ok!");
255 | }
256 | }
257 |
--------------------------------------------------------------------------------
/src/conti_radar/src/radar_can_conti.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by zxkj on 18-12-01.
3 | //
4 | #include "radar_can_conti.h"
5 | #include
6 |
7 |
8 | RadarCan_Conti::RadarCan_Conti()
9 | {
10 | //channel0,500K,no extern,no remote,normal mode,double filter,acccode,accmode,can status
11 | CanParameters can_init_parameter_;
12 | can_init_parameter_.can_channel_index = 0; //0:channel0, 1:channel1
13 | can_init_parameter_.can_baudrate = 500; //set baudrate 500K
14 | can_init_parameter_.can_is_extern = 0; //0:standard frame, 1:extern frame
15 | can_init_parameter_.can_is_remote = 0; //0:data frame, 1:remote frame
16 | can_init_parameter_.can_work_mode = 0; //0:normal, 1:listening only
17 | can_init_parameter_.can_filter_mode = 0; //0:no use, 1:double filter, 2:single filter
18 | can_init_parameter_.can_acc_code = 0x000080C7; //not use
19 | can_init_parameter_.can_acc_mask = 0xFFFF7F00; //not use
20 | can_init_parameter_.can_status = -1; //
21 |
22 | can_parameters_.push_back(can_init_parameter_);//can0
23 | }
24 |
25 | bool RadarCan_Conti::checkInfo()
26 | {
27 | bool flag = true;
28 | return flag;
29 | }
30 |
31 | void RadarCan_Conti::setup()
32 | {
33 | node_handle_.param("/conti_radar/recv_info_freq", recv_info_freq_, 1000);
34 | node_handle_.param("/conti_radar/max_missing_times", max_missing_times_, 100);
35 |
36 | node_handle_.param("/conti_radar/long_offset_mid", long_offset_mid_, 0.0);//3.6
37 | node_handle_.param("/conti_radar/lat_offset_mid", lat_offset_mid_, 0.0);//0.23
38 | node_handle_.param("/conti_radar/angular_deviation_id", angular_deviation_mid_, 0.0);
39 |
40 | node_handle_.param("/conti_radar/long_offset_left", long_offset_left_, 6.0);
41 | node_handle_.param("/conti_radar/lat_offset_left", lat_offset_left_, -1.12);
42 | node_handle_.param("/conti_radar/angular_deviation_left", angular_deviation_left_, 165.0);
43 |
44 | node_handle_.param("/conti_radar/long_offset_right", long_offset_right_, 6.0);
45 | node_handle_.param("/conti_radar/lat_offset_right", lat_offset_right_, 1.12);
46 | node_handle_.param("/conti_radar/angular_deviation_right", angular_deviation_right_, 15.0);
47 |
48 | node_handle_.param("/conti_radar/check_msg_freq", check_msg_freq_, 10);
49 | node_handle_.param("/conti_radar/send_req_vehicle_msg_freq", send_req_vehicle_msg_freq_, 50);
50 |
51 |
52 | angular_deviation_mid_ = angular_deviation_mid_ / 180 * M_PI;
53 | angular_deviation_left_ = angular_deviation_left_ / 180 * M_PI;
54 | angular_deviation_right_ = angular_deviation_right_ / 180 * M_PI;
55 |
56 | object_mid_num_ = -1;
57 | object_left_num_ = -1;
58 | object_right_num_ = -1;
59 |
60 | general_info_arr_mid_.clear();
61 | quality_info_arr_mid_.clear();
62 | extended_info_arr_mid_.clear();
63 |
64 | general_info_arr_left_.clear();
65 | quality_info_arr_left_.clear();
66 | extended_info_arr_left_.clear();
67 |
68 | general_info_arr_right_.clear();
69 | quality_info_arr_right_.clear();
70 | extended_info_arr_right_.clear();
71 | }
72 |
73 |
74 | void RadarCan_Conti::leftMessagePub()
75 | {
76 | // if(object_left_num_ == -1)//if not reassign the object_num_ in OBJECT_LIST_STATUS branch
77 | // {
78 | // general_info_arr_left_.clear();
79 | // quality_info_arr_left_.clear();
80 | // extended_info_arr_left_.clear();
81 |
82 | // // ROS_ERROR("error num of left object");
83 | // }
84 | // else if(object_left_num_ >= 0)
85 | // {
86 | // if(object_left_num_ == general_info_arr_left_.size() &&
87 | // object_left_num_ == quality_info_arr_left_.size() &&
88 | // object_left_num_ == extended_info_arr_left_.size()) //in a period recv all the CAN frame
89 | // {
90 | // conti_radar_msgs::Object object_;
91 | // conti_radar_msgs::Objects objects_msgs_;
92 |
93 | // for(size_t i = 0; i < general_info_arr_left_.size(); ++i)
94 | // {
95 | // object_.id = general_info_arr_left_[i].object_id_;
96 |
97 | // double object_box_center_x = general_info_arr_left_[i].object_dist_long_;
98 | // double object_box_center_y = general_info_arr_left_[i].object_dist_lat_;
99 |
100 | // object_.object_box_center.x = object_box_center_x * cos(angular_deviation_left_) - object_box_center_y * sin(angular_deviation_left_) + long_offset_left_;
101 | // object_.object_box_center.y = object_box_center_x * sin(angular_deviation_left_) + object_box_center_y * cos(angular_deviation_left_) + lat_offset_left_;
102 | // // double temp = object_.object_box_center.y;//for lux object
103 | // // object_.object_box_center.y = -object_.object_box_center.x;//for lux object
104 | // // object_.object_box_center.x = temp;
105 |
106 | // object_.relative_velocity.x = general_info_arr_left_[i].object_vre_long_ * cos(angular_deviation_left_) - general_info_arr_left_[i].object_vre_lat_ * sin(angular_deviation_left_);
107 | // object_.relative_velocity.y = general_info_arr_left_[i].object_vre_long_ * sin(angular_deviation_left_) + general_info_arr_left_[i].object_vre_lat_ * cos(angular_deviation_left_);
108 | // // temp = object_.relative_velocity.y;//for lux object
109 | // // object_.relative_velocity.y = -object_.relative_velocity.x;//for lux object
110 | // // object_.relative_velocity.x = temp;
111 |
112 | // for(size_t j = 0; j < quality_info_arr_left_.size(); ++j)
113 | // {
114 | // if(object_.id == quality_info_arr_left_[j].object_id_)
115 | // {
116 | // //if need any other quality info message can manage here
117 | // }
118 | // }
119 | // for(size_t k = 0; k < extended_info_arr_left_.size(); ++k)
120 | // {
121 | // if(object_.id == extended_info_arr_left_[k].object_id_)
122 | // {
123 | // object_.object_box_size.x = extended_info_arr_left_[k].object_length_;
124 | // object_.object_box_size.y = extended_info_arr_left_[k].object_width_;
125 | // object_.classification = extended_info_arr_left_[k].object_class_;
126 | // //object_.object_box_orientation = -extended_info_arr_left_[k].object_orientation_angel_ - 75.0;//rotate box orientation;
127 |
128 | // object_.relative_acceleration.x = extended_info_arr_left_[k].object_arel_long_ * cos(angular_deviation_left_) - extended_info_arr_left_[k].object_arel_lat_ * sin(angular_deviation_left_);
129 | // object_.relative_acceleration.y = extended_info_arr_left_[k].object_arel_long_ * sin(angular_deviation_left_) + extended_info_arr_left_[k].object_arel_lat_ * cos(angular_deviation_left_);
130 | // // temp = object_.relative_acceleration.y;//for lux object
131 | // // object_.relative_acceleration.y = -object_.relative_acceleration.x;//for lux object
132 | // // object_.relative_acceleration.x = temp;
133 | // }
134 | // }
135 | // objects_msgs_.objects.push_back(object_);
136 | // }
137 |
138 | // objects_msgs_.header.frame_id = "conti_radar_left";//conti_radar_left
139 | // objects_msgs_.header.stamp = ros::Time::now();
140 | // left_radar_info_pub_.publish(objects_msgs_);
141 |
142 | // general_info_arr_left_.clear();
143 | // quality_info_arr_left_.clear();
144 | // extended_info_arr_left_.clear();
145 |
146 | // object_left_num_ = -1;
147 | // }
148 | // }
149 | }
150 |
151 |
152 | void RadarCan_Conti::midMessagePub()
153 | {
154 | // ROS_INFO("general: %d",general_info_arr_mid_.size());
155 | // ROS_INFO("quality: %d",quality_info_arr_mid_.size());
156 | // ROS_INFO("extended: %d",extended_info_arr_mid_.size());
157 |
158 | if(object_mid_num_ == -1)//if not reassign the object_num_ in OBJECT_LIST_STATUS branch
159 | {
160 | general_info_arr_mid_.clear();
161 | quality_info_arr_mid_.clear();
162 | extended_info_arr_mid_.clear();
163 | // ROS_ERROR("error num of mid object");
164 | }
165 | else if(object_mid_num_ >= 0)
166 | {
167 | if(object_mid_num_ == general_info_arr_mid_.size() &&
168 | object_mid_num_ == quality_info_arr_mid_.size() &&
169 | object_mid_num_ == extended_info_arr_mid_.size()) //in a period recv all the CAN frame
170 | {
171 | conti_radar_msgs::conti_Object object_;
172 | conti_radar_msgs::conti_Objects objects_msgs_;
173 |
174 | for(size_t i = 0; i < general_info_arr_mid_.size(); ++i)
175 | {
176 | object_.ID = general_info_arr_mid_[i].object_id_ + 200;
177 | object_.Object_DistLong = general_info_arr_mid_[i].object_dist_long_;
178 | object_.Object_DistLat = general_info_arr_mid_[i].object_dist_lat_;
179 | object_.Object_VrelLong = general_info_arr_mid_[i].object_vre_long_;
180 | object_.Object_VrelLat = general_info_arr_mid_[i].object_vre_lat_;
181 | object_.Object_DynProp = general_info_arr_mid_[i].object_dyn_prop_;
182 | object_.Object_RCS = general_info_arr_mid_[i].object_rcs_;
183 |
184 | for(size_t j = 0; j < quality_info_arr_mid_.size(); ++j)
185 | {
186 | if(object_.ID == quality_info_arr_mid_[j].object_id_ + 200)
187 | {
188 | object_.Obj_ProbOfExist = quality_info_arr_mid_[j].object_prob_of_exist_;
189 | }
190 | }
191 | for(size_t k = 0; k < extended_info_arr_mid_.size(); ++k)
192 | {
193 | if(object_.ID == extended_info_arr_mid_[k].object_id_ + 200)
194 | {
195 | object_.Object_OrientationAngel = extended_info_arr_mid_[k].object_orientation_angel_;
196 | object_.Object_Length = extended_info_arr_mid_[k].object_length_;
197 | object_.Object_Width = extended_info_arr_mid_[k].object_width_;
198 | }
199 | }
200 | objects_msgs_.objects.push_back(object_);
201 | }
202 | objects_msgs_.header.frame_id = "conti_radar_mid";//conti_radar_mid
203 | objects_msgs_.header.stamp = ros::Time::now();
204 | mid_radar_info_pub_.publish(objects_msgs_);
205 |
206 | general_info_arr_mid_.clear();
207 | quality_info_arr_mid_.clear();
208 | extended_info_arr_mid_.clear();
209 |
210 | object_mid_num_ = -1;
211 | }
212 | }
213 | }
214 |
215 |
216 | void RadarCan_Conti::rightMessagePub()
217 | {
218 | // if(object_right_num_ == -1)//if not reassign the object_num_ in OBJECT_LIST_STATUS branch
219 | // {
220 |
221 | // general_info_arr_right_.clear();
222 | // quality_info_arr_right_.clear();
223 | // extended_info_arr_right_.clear();
224 |
225 | // // ROS_ERROR("error num of right object");
226 | // }
227 | // else if(object_right_num_ >= 0)
228 | // {
229 | // if(object_right_num_ == general_info_arr_right_.size() &&
230 | // object_right_num_ == quality_info_arr_right_.size() &&
231 | // object_right_num_ == extended_info_arr_right_.size()) //in a period recv all the CAN frame
232 | // {
233 | // conti_radar_msgs::Object object_;
234 | // conti_radar_msgs::Objects objects_msgs_;
235 |
236 | // for(size_t i = 0; i < general_info_arr_right_.size(); ++i)
237 | // {
238 | // object_.id = general_info_arr_right_[i].object_id_ + 400;
239 |
240 | // double object_box_center_x = general_info_arr_right_[i].object_dist_long_;
241 | // double object_box_center_y = general_info_arr_right_[i].object_dist_lat_;
242 |
243 | // object_.object_box_center.x = object_box_center_x * cos(angular_deviation_right_) + object_box_center_y * sin(angular_deviation_right_) + long_offset_right_;
244 | // object_.object_box_center.y = -(object_box_center_x * sin(angular_deviation_right_) - object_box_center_y * cos(angular_deviation_right_)) + lat_offset_right_;
245 | // // double temp = object_.object_box_center.y;//for lux object
246 | // // object_.object_box_center.y = -object_.object_box_center.x;//for lux object
247 | // // object_.object_box_center.x = temp;
248 |
249 | // object_.relative_velocity.x = general_info_arr_right_[i].object_vre_long_ * cos(angular_deviation_right_) + general_info_arr_right_[i].object_vre_lat_ * sin(angular_deviation_right_);
250 | // object_.relative_velocity.y = -(general_info_arr_right_[i].object_vre_long_ * sin(angular_deviation_right_) - general_info_arr_right_[i].object_vre_lat_ * cos(angular_deviation_right_));
251 | // // temp = object_.relative_velocity.y;//for lux object
252 | // // object_.relative_velocity.y = -object_.relative_velocity.x;//for lux object
253 | // // object_.relative_velocity.x = temp;
254 |
255 | // for(size_t j = 0; j < quality_info_arr_right_.size(); ++j)
256 | // {
257 | // if(object_.id == quality_info_arr_right_[j].object_id_ + 400)
258 | // {
259 | // //if need any other quality info message can manage here
260 | // }
261 | // }
262 | // for(size_t k = 0; k < extended_info_arr_right_.size(); ++k)
263 | // {
264 | // if(object_.id == extended_info_arr_right_[k].object_id_ + 400)
265 | // {
266 | // object_.object_box_size.x = extended_info_arr_right_[k].object_length_;
267 | // object_.object_box_size.y = extended_info_arr_right_[k].object_width_;
268 | // object_.classification = extended_info_arr_right_[k].object_class_;
269 | // //object_.object_box_orientation = extended_info_arr_right_[k].object_orientation_angel_ + 75;//rotate box orientation;
270 | // object_.relative_acceleration.x = extended_info_arr_right_[k].object_arel_long_ * cos(angular_deviation_right_) + extended_info_arr_right_[k].object_arel_lat_ * sin(angular_deviation_right_);
271 | // object_.relative_acceleration.y = -(extended_info_arr_right_[k].object_arel_long_ * sin(angular_deviation_right_) - extended_info_arr_right_[k].object_arel_lat_ * cos(angular_deviation_right_));
272 | // // temp = object_.relative_acceleration.y;//for lux object
273 | // // object_.relative_acceleration.y = -object_.relative_acceleration.x;//for lux object
274 | // // object_.relative_acceleration.x = temp;
275 | // }
276 | // }
277 | // objects_msgs_.objects.push_back(object_);
278 | // }
279 |
280 | // objects_msgs_.header.frame_id = "conti_radar_right";//conti_radar_right
281 | // objects_msgs_.header.stamp = ros::Time::now();
282 | // right_radar_info_pub_.publish(objects_msgs_);
283 |
284 | // general_info_arr_right_.clear();
285 | // quality_info_arr_right_.clear();
286 | // extended_info_arr_right_.clear();
287 |
288 | // object_right_num_ = -1;
289 | // }
290 | // }
291 | }
292 |
293 |
294 | void RadarCan_Conti::transformCanToInfo(std::vector& can_frames, int len)
295 | {
296 | for(int i = 0; i < len; i++)
297 | {
298 | int current_id = can_frames[i].uID;
299 | switch (current_id)
300 | {
301 | // case RADAR_STATE_MID:
302 | // {
303 | // radar_state_.unPackBytes(can_frames[i]);
304 | // ROS_ERROR("getMaxDistanceCfg:%d",radar_state_.getMaxDistanceCfg());
305 | // ROS_ERROR("getErrorState:%d",radar_state_.getErrorState());
306 | // ROS_ERROR("getSensorID:%d",radar_state_.getSensorID());
307 | // ROS_ERROR("getSortIndex:%d",radar_state_.getSortIndex());
308 | // ROS_ERROR("getRadarPower:%d",radar_state_.getRadarPower());
309 | // ROS_ERROR("getOutputType:%d",radar_state_.getOutputType());
310 | // ROS_ERROR("getSendQuality:%d",radar_state_.getSendQuality());
311 | // ROS_ERROR("getSendExtInfo:%d",radar_state_.getSendExtInfo());
312 | // ROS_ERROR("getMotionRxState:%d",radar_state_.getMotionRxState());
313 | // ROS_ERROR("getRCS_Threshold:%d",radar_state_.getRCS_Threshold());
314 | // }
315 | case OBJECT_LIST_STATUS_MID://)0x60A
316 | {
317 | object_list_status_.unPackBytes(can_frames[i]);
318 | object_mid_num_= object_list_status_.getNumOfObj();
319 | general_info_arr_mid_.clear();
320 | quality_info_arr_mid_.clear();
321 | extended_info_arr_mid_.clear();
322 |
323 | ROS_INFO("I CAN detect %d objects in mid radar",object_mid_num_);
324 |
325 | }
326 | break;
327 | case OBJECT_GENERAL_INFO_MID:
328 | {
329 | object_general_info_.unPackBytes(can_frames[i]);
330 | GeneralInfo general_info_;
331 | general_info_ = object_general_info_.getGeneralInfo();
332 | general_info_arr_mid_.emplace_back(general_info_);
333 | }
334 | break;
335 | case OBJECT_QUALITY_INFO_MID:
336 | {
337 | object_quality_info_.unPackBytes(can_frames[i]);
338 | QualityInfo quality_info_;
339 | quality_info_ = object_quality_info_.getQualityInfo();
340 | quality_info_arr_mid_.emplace_back(quality_info_);
341 | }
342 | break;
343 | case OBJECT_EXTENDED_INFO_MID:
344 | {
345 | object_extended_info_.unPackBytes(can_frames[i]);
346 | ExtendedInfo extended_info_;
347 | extended_info_ = object_extended_info_.getExtendedInfo();
348 | extended_info_arr_mid_.emplace_back(extended_info_);
349 | }
350 | break;
351 | case OBJECT_LIST_STATUS_LEFT:
352 | {
353 | object_list_status_.unPackBytes(can_frames[i]);
354 | object_left_num_= object_list_status_.getNumOfObj();
355 | general_info_arr_left_.clear();
356 | quality_info_arr_left_.clear();
357 | extended_info_arr_left_.clear();
358 |
359 | ROS_INFO("I CAN detect %d objects in left radar",object_left_num_);
360 | }
361 | break;
362 | case OBJECT_GENERAL_INFO_LEFT:
363 | {
364 | object_general_info_.unPackBytes(can_frames[i]);
365 | GeneralInfo general_info_;
366 | general_info_ = object_general_info_.getGeneralInfo();
367 | general_info_arr_left_.emplace_back(general_info_);
368 | }
369 | break;
370 | case OBJECT_QUALITY_INFO_LEFT:
371 | {
372 | object_quality_info_.unPackBytes(can_frames[i]);
373 | QualityInfo quality_info_;
374 | quality_info_ = object_quality_info_.getQualityInfo();
375 | quality_info_arr_left_.emplace_back(quality_info_);
376 | }
377 | break;
378 | case OBJECT_EXTENDED_INFO_LEFT:
379 | {
380 | object_extended_info_.unPackBytes(can_frames[i]);
381 | ExtendedInfo extended_info_;
382 | extended_info_ = object_extended_info_.getExtendedInfo();
383 | extended_info_arr_left_.emplace_back(extended_info_);
384 | }
385 | break;
386 | case OBJECT_LIST_STATUS_RIGHT:
387 | {
388 | object_list_status_.unPackBytes(can_frames[i]);
389 | object_right_num_= object_list_status_.getNumOfObj();
390 | general_info_arr_right_.clear();
391 | quality_info_arr_right_.clear();
392 | extended_info_arr_right_.clear();
393 |
394 | ROS_INFO("I CAN detect %d objects in right radar",object_right_num_);
395 | }
396 | break;
397 | case OBJECT_GENERAL_INFO_RIGHT:
398 | {
399 | object_general_info_.unPackBytes(can_frames[i]);
400 | GeneralInfo general_info_;
401 | general_info_ = object_general_info_.getGeneralInfo();
402 | general_info_arr_right_.emplace_back(general_info_);
403 | }
404 | break;
405 | case OBJECT_QUALITY_INFO_RIGHT:
406 | {
407 | object_quality_info_.unPackBytes(can_frames[i]);
408 | QualityInfo quality_info_;
409 | quality_info_ = object_quality_info_.getQualityInfo();
410 | quality_info_arr_right_.emplace_back(quality_info_);
411 | }
412 | break;
413 | case OBJECT_EXTENDED_INFO_RIGHT:
414 | {
415 | object_extended_info_.unPackBytes(can_frames[i]);
416 | ExtendedInfo extended_info_;
417 | extended_info_ = object_extended_info_.getExtendedInfo();
418 | extended_info_arr_right_.emplace_back(extended_info_);
419 | }
420 | break;
421 | default:
422 | continue;
423 | }
424 | midMessagePub(); // 在里面判断这一组是否凑齐。凑齐了就发送。
425 | leftMessagePub();
426 | rightMessagePub();
427 | }
428 |
429 | }
430 |
431 |
432 |
433 |
434 |
--------------------------------------------------------------------------------