mirror of
https://git.ti.com/git/mmwave_radar/mmwave_ti_ros.git
synced 2026-05-21 01:12:08 +00:00
Merge pull request #3 in MITL/mmwave_ti_ros from mmWaveCLIFix to master
* commit '13c8c52fc0f483fe09eb7b178215cfd988b6a24e': add /mmWaveCLI into ti_mmwave_sensor Minimal_quad now correct
This commit is contained in:
@@ -76,6 +76,8 @@ class mmWaveCommSrv : public nodelet::Nodelet
|
||||
std::string mySerialPort;
|
||||
|
||||
int myBaudRate;
|
||||
|
||||
std::string mmWaveCLIName;
|
||||
}; //Class mmWaveCommSrv
|
||||
|
||||
} //namespace ti_mmwave_rospkg
|
||||
|
||||
@@ -12,18 +12,21 @@
|
||||
|
||||
<!-- mmWave_Manager node -->
|
||||
<node pkg="ti_mmwave_rospkg" type="ti_mmwave_rospkg" name="ti_mmwave" ns="radar_1" output="screen">
|
||||
<param name="command_port" value="/dev/mmWave_00CE0E81_00" />
|
||||
<param name="command_port" value="/dev/mmWave_00CE0FCA_00" />
|
||||
<param name="command_rate" value="115200" />
|
||||
<param name="data_port" value="/dev/mmWave_00CE0E81_01" />
|
||||
<param name="data_port" value="/dev/mmWave_00CE0FCA_01" />
|
||||
<param name="data_rate" value="921600" />
|
||||
<param name="max_allowed_elevation_angle_deg" value="$(arg max_allowed_elevation_angle_deg)" />
|
||||
<param name="max_allowed_azimuth_angle_deg" value="$(arg max_allowed_azimuth_angle_deg)" />
|
||||
<param name="frame_id" value="ti_mmwave_1"/>
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI_1" />
|
||||
<remap from="/ti_mmwave/radar_scan_pcl" to="/ti_mmwave/radar_scan_pcl_1"/>
|
||||
</node>
|
||||
|
||||
<!-- mmWaveQuickConfig node (terminates after configuring mmWave sensor) -->
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_1" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" />
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_1" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen">
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI_1" />
|
||||
</node>
|
||||
|
||||
<node pkg="tf" type="static_transform_publisher" name="radar_baselink_1" args="0 -0.19 0.18 1.57 3.1415 0 base_link ti_mmwave_1 100"/>
|
||||
|
||||
|
||||
@@ -12,18 +12,21 @@
|
||||
|
||||
<!-- mmWave_Manager node -->
|
||||
<node pkg="ti_mmwave_rospkg" type="ti_mmwave_rospkg" name="ti_mmwave" ns="radar_0" output="screen">
|
||||
<param name="command_port" value="/dev/mmWave_00CE0FCA_00" />
|
||||
<param name="command_port" value="/dev/mmWave_00CE0E81_00" />
|
||||
<param name="command_rate" value="115200" />
|
||||
<param name="data_port" value="/dev/mmWave_00CE0FCA_01" />
|
||||
<param name="data_port" value="/dev/mmWave_00CE0E81_01" />
|
||||
<param name="data_rate" value="921600" />
|
||||
<param name="max_allowed_elevation_angle_deg" value="$(arg max_allowed_elevation_angle_deg)" />
|
||||
<param name="max_allowed_azimuth_angle_deg" value="$(arg max_allowed_azimuth_angle_deg)" />
|
||||
<param name="frame_id" value="ti_mmwave_0"/>
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI_0" />
|
||||
<remap from="/ti_mmwave/radar_scan_pcl" to="/ti_mmwave/radar_scan_pcl_0"/>
|
||||
</node>
|
||||
|
||||
<!-- mmWaveQuickConfig node (terminates after configuring mmWave sensor) -->
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_0" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" />
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_0" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" >
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI_0" />
|
||||
</node>
|
||||
|
||||
<node pkg="tf" type="static_transform_publisher" name="radar_baselink_0" args="0.19 0 0.18 0 0 3.1415 base_link ti_mmwave_0 100"/>
|
||||
<!--
|
||||
|
||||
@@ -19,11 +19,14 @@
|
||||
<param name="max_allowed_elevation_angle_deg" value="$(arg max_allowed_elevation_angle_deg)" />
|
||||
<param name="max_allowed_azimuth_angle_deg" value="$(arg max_allowed_azimuth_angle_deg)" />
|
||||
<param name="frame_id" value="ti_mmwave_2"/>
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI_2" />
|
||||
<remap from="/ti_mmwave/radar_scan_pcl" to="/ti_mmwave/radar_scan_pcl_2"/>
|
||||
</node>
|
||||
|
||||
<!-- mmWaveQuickConfig node (terminates after configuring mmWave sensor) -->
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_2" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" />
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_2" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" >
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI_2" />
|
||||
</node>
|
||||
|
||||
<node pkg="tf" type="static_transform_publisher" name="radar_baselink_2" args="-.19 0 0.18 3.14 0 3.14 base_link ti_mmwave_2 100"/>
|
||||
|
||||
|
||||
@@ -12,18 +12,21 @@
|
||||
|
||||
<!-- mmWave_Manager node -->
|
||||
<node pkg="ti_mmwave_rospkg" type="ti_mmwave_rospkg" name="ti_mmwave" ns="radar_3" output="screen">
|
||||
<param name="command_port" value="/dev/mmWave_00D83B50_00" />
|
||||
<param name="command_port" value="/dev/mmWave_00CE0E83_00" />
|
||||
<param name="command_rate" value="115200" />
|
||||
<param name="data_port" value="/dev/mmWave_00D83B50_01" />
|
||||
<param name="data_port" value="/dev/mmWave_00CE0E83_01" />
|
||||
<param name="data_rate" value="921600" />
|
||||
<param name="max_allowed_elevation_angle_deg" value="$(arg max_allowed_elevation_angle_deg)" />
|
||||
<param name="max_allowed_azimuth_angle_deg" value="$(arg max_allowed_azimuth_angle_deg)" />
|
||||
<param name="frame_id" value="ti_mmwave_3"/>
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI_3" />
|
||||
<remap from="/ti_mmwave/radar_scan_pcl" to="/ti_mmwave/radar_scan_pcl_3"/>
|
||||
</node>
|
||||
|
||||
<!-- mmWaveQuickConfig node (terminates after configuring mmWave sensor) -->
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_3" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" />
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_3" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" >
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI_3" />
|
||||
</node>
|
||||
|
||||
<node pkg="tf" type="static_transform_publisher" name="radar_baselink_3" args="0 0.19 0.18 -1.57 3.1415 0 base_link ti_mmwave_3 100"/>
|
||||
|
||||
|
||||
@@ -19,11 +19,14 @@
|
||||
<param name="max_allowed_elevation_angle_deg" value="$(arg max_allowed_elevation_angle_deg)" />
|
||||
<param name="max_allowed_azimuth_angle_deg" value="$(arg max_allowed_azimuth_angle_deg)" />
|
||||
<param name="frame_id" value="ti_mmwave"/>
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI" />
|
||||
<remap from="/ti_mmwave/radar_scan_pcl" to="/ti_mmwave/radar_scan_pcl"/>
|
||||
</node>
|
||||
|
||||
<!-- mmWaveQuickConfig node (terminates after configuring mmWave sensor) -->
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="mmWaveQuickConfig" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" />
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="mmWaveQuickConfig" args="$(find ti_mmwave_rospkg)/cfg/$(arg device)_$(arg config).cfg" output="screen" >
|
||||
<param name="mmWaveCLI_name" value="/mmWaveCLI" />
|
||||
</node>
|
||||
|
||||
<node pkg="tf2_ros" type="static_transform_publisher" name="radar_baselink_0" args="0.19 0 0.18 0 0 3.1415 base_link ti_mmwave"/>
|
||||
|
||||
|
||||
@@ -53,11 +53,12 @@ void mmWaveCommSrv::onInit()
|
||||
private_nh2.getParam("command_port", mySerialPort);
|
||||
|
||||
private_nh2.getParam("command_rate", myBaudRate);
|
||||
private_nh2.getParam("mmWaveCLI_name", mmWaveCLIName);
|
||||
|
||||
ROS_INFO("mmWaveCommSrv: command_port = %s", mySerialPort.c_str());
|
||||
ROS_INFO("mmWaveCommSrv: command_rate = %d", myBaudRate);
|
||||
|
||||
commSrv = private_nh.advertiseService("/mmWaveCLI", &mmWaveCommSrv::commSrv_cb, this);
|
||||
commSrv = private_nh.advertiseService(mmWaveCLIName, &mmWaveCommSrv::commSrv_cb, this);
|
||||
|
||||
NODELET_DEBUG("mmWaveCommsrv: Finished onInit function");
|
||||
}
|
||||
|
||||
@@ -47,18 +47,20 @@
|
||||
int main(int argc, char **argv) {
|
||||
ros::init(argc, argv, "mmWaveQuickConfig");
|
||||
ros::NodeHandle nh;
|
||||
ros::NodeHandle private_nh("~");
|
||||
ti_mmwave_rospkg::mmWaveCLI srv;
|
||||
if (argc != 2) {
|
||||
ROS_INFO("mmWaveQuickConfig: usage: mmWaveQuickConfig /file_directory/params.cfg");
|
||||
return 1;
|
||||
} else
|
||||
ROS_INFO("mmWaveQuickConfig: Configuring mmWave device using config file: %s", argv[1]);
|
||||
|
||||
ros::ServiceClient client = nh.serviceClient<ti_mmwave_rospkg::mmWaveCLI>("/mmWaveCLI");
|
||||
std::string mmWaveCLIName;
|
||||
private_nh.getParam("mmWaveCLI_name", mmWaveCLIName);
|
||||
ros::ServiceClient client = nh.serviceClient<ti_mmwave_rospkg::mmWaveCLI>(mmWaveCLIName);
|
||||
std::ifstream myParams;
|
||||
ti_mmwave_rospkg::ParameterParser parser;
|
||||
//wait for service to become available
|
||||
ros::service::waitForService("/mmWaveCLI", 10000);
|
||||
ros::service::waitForService(mmWaveCLIName, 10000);
|
||||
|
||||
//wait 0.5 secs to avoid multi-sensor conflicts
|
||||
ros::Duration(0.5).sleep();
|
||||
|
||||
Reference in New Issue
Block a user