From f900057989181a6b8d18a518d15e5b01101b0b50 Mon Sep 17 00:00:00 2001 From: isvogor Date: Fri, 12 May 2017 11:04:42 -0400 Subject: [PATCH] localpos topic to yaml --- include/roscontroller.h | 1 + launch/launch_config/solo.yaml | 1 + script/testsolo.bo | Bin 3809 -> 3809 bytes src/roscontroller.cpp | 6 +++--- 4 files changed, 5 insertions(+), 3 deletions(-) diff --git a/include/roscontroller.h b/include/roscontroller.h index 4169307..74db7ae 100644 --- a/include/roscontroller.h +++ b/include/roscontroller.h @@ -111,6 +111,7 @@ private: ros::Subscriber Robot_id_sub; ros::Subscriber relative_altitude_sub; + std::string local_pos_sub_name; ros::Subscriber local_pos_sub; double local_pos_new[3]; diff --git a/launch/launch_config/solo.yaml b/launch/launch_config/solo.yaml index c53989a..6ad2ec8 100644 --- a/launch/launch_config/solo.yaml +++ b/launch/launch_config/solo.yaml @@ -6,6 +6,7 @@ topics: setpoint: mavros/setpoint_position/local armclient: mavros/cmd/arming modeclient: mavros/set_mode + localpos: /mavros/local_position/pose stream: mavros/set_stream_rate altitude: mavros/global_position/rel_alt type: diff --git a/script/testsolo.bo b/script/testsolo.bo index d44323f3d95452a9e324e599bece697ec63f0381..294076a1b82734a464ecc21f47de0694be114e9d 100644 GIT binary patch delta 49 vcmaDT`%renVh)x5Ltky=7=S>Y2}sDOo#kL)P|yJ~#lfO-Ao(stream_client_name); users_sub = n_c.subscribe("users_pos", 1000, &roscontroller::users_pos,this); - - local_pos_sub = n_c.subscribe("/mavros/local_position/pose", 1000, &roscontroller::local_pos_callback, this); + local_pos_sub = n_c.subscribe(local_pos_sub_name, 1000, &roscontroller::local_pos_callback, this); multi_msg=true; }