Skip to content

Commit

Permalink
add params for hypothetical radar
Browse files Browse the repository at this point in the history
  • Loading branch information
meshvaD committed Jul 23, 2024
1 parent 9fe4b27 commit c3e1a0b
Show file tree
Hide file tree
Showing 4 changed files with 54 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,7 @@ install(

# Install launch files.
install(DIRECTORY
config
launch
DESTINATION share/${PROJECT_NAME}
)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
radar_node:
ros__parameters:
can_channel: "can0"
#topic name of list of objects detected
object_list_topic_name: "object_list"
#topic name of array of markers used to visualize objects detected
marker_array_topic_name: "marker_array"
#topic name of array of radar tracks detected
radar_tracks_topic_name: "radar_tracks"
#topic name of array of obstacle detected, corresponds with radar tracks
obstacle_array_topic_name: "obstacle_array"

radar_0:
#link of radar, should be relative to base_link
link_name: "front_radar_link"
#set filter active flag on filter config index
active: [true, false, false, false, false, true, false, false, true, false, false, false, false, false, false]
#set filter valid flag on filter config index
valid: [true, false, false, false, false, true, false, false, true, false, false, false, false, false, false]
filtercfg_min_nofobj: 0
filtercfg_max_nofobj: 5
filtercfg_min_distance: 0.0
filtercfg_max_distance: 409.0
filtercfg_min_azimuth: 0.0
filtercfg_max_azimuth: 100.0
filtercfg_min_vreloncome: 0.0
filtercfg_max_vreloncome: 128.0
filtercfg_min_vreldepart: 0.0
filtercfg_max_vreldepart: 128.0
filtercfg_min_rcs: 50.0
filtercfg_max_rcs: 80.0
filtercfg_min_lifetime: 0.0
filtercfg_max_lifetime: 409.0
filtercfg_min_size: 0.0
filtercfg_max_size: 102.0
filtercfg_min_probexists: 5
filtercfg_max_probexists: 7
filtercfg_min_y: 0.0
filtercfg_max_y: 818.0
filtercfg_min_x: 0.0
filtercfg_max_x: 0.0
filtercfg_min_vyrightleft: 0.0
filtercfg_max_vyrightleft: 128.0
filtercfg_min_vxoncome: 0.0
filtercfg_max_vxoncome: 128.0
filtercfg_min_vyleftright: 0.0
filtercfg_max_vyleftright: 128.0
filtercfg_min_vxdepart: 0.0
filtercfg_max_vxdepart: 128.0
Original file line number Diff line number Diff line change
Expand Up @@ -195,12 +195,12 @@ radar_conti_ars408::on_configure(const rclcpp_lifecycle::State &) {
} while (more_params);

can_frame_subscriber_ = this->create_subscription<can_msgs::msg::Frame>(
"/from_can_bus", transient_local_qos,
"/from_can_bus", 10,
std::bind(&radar_conti_ars408::can_receive_callback, this, std::placeholders::_1));
can_frame_publisher_ =
this->create_publisher<can_msgs::msg::Frame>("/to_can_bus", transient_local_qos);
this->create_publisher<can_msgs::msg::Frame>("/to_can_bus", 10);
radar_packet_publisher_ =
this->create_publisher<radar_msgs::msg::RadarPacket>("/radar_packet", transient_local_qos);
this->create_publisher<radar_msgs::msg::RadarPacket>("/radar_packet", 10);

object_count = 0.0;
set_filter_service_ = create_service<radar_conti_ars408_msgs::srv::SetFilter>(
Expand Down
2 changes: 1 addition & 1 deletion src/interfacing/sensor_interfacing/setup.sh
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ set -e

# Display configuration
echo Using following configuration
echo VCAN_INTERFACE: "${VCAN_INTERFACE:=can0}"
echo VCAN_INTERFACE: "${VCAN_INTERFACE:=vcan0}"
echo VCAN_SOURCE_PORT: "${VCAN_SOURCE_PORT:=6000}"
echo VCAN_TARGET_IP: "${VCAN_TARGET_IP:=172.17.0.1}"
echo VCAN_TARGET_PORT: "$VCAN_TARGET_PORT"
Expand Down

0 comments on commit c3e1a0b

Please sign in to comment.