localpos topic to yaml

This commit is contained in:
isvogor 2017-05-12 11:04:42 -04:00
parent 60553fd55d
commit f900057989
4 changed files with 5 additions and 3 deletions

View File

@ -111,6 +111,7 @@ private:
ros::Subscriber Robot_id_sub; ros::Subscriber Robot_id_sub;
ros::Subscriber relative_altitude_sub; ros::Subscriber relative_altitude_sub;
std::string local_pos_sub_name;
ros::Subscriber local_pos_sub; ros::Subscriber local_pos_sub;
double local_pos_new[3]; double local_pos_new[3];

View File

@ -6,6 +6,7 @@ topics:
setpoint: mavros/setpoint_position/local setpoint: mavros/setpoint_position/local
armclient: mavros/cmd/arming armclient: mavros/cmd/arming
modeclient: mavros/set_mode modeclient: mavros/set_mode
localpos: /mavros/local_position/pose
stream: mavros/set_stream_rate stream: mavros/set_stream_rate
altitude: mavros/global_position/rel_alt altitude: mavros/global_position/rel_alt
type: type:

Binary file not shown.

View File

@ -215,7 +215,8 @@ namespace rosbzz_node{
else {ROS_ERROR("Provide a mode client name in Launch file"); system("rosnode kill rosbuzz_node");} else {ROS_ERROR("Provide a mode client name in Launch file"); system("rosnode kill rosbuzz_node");}
if(node_handle.getParam("topics/stream", stream_client_name)); if(node_handle.getParam("topics/stream", stream_client_name));
else {ROS_ERROR("Provide a mode client name in Launch file"); system("rosnode kill rosbuzz_node");} else {ROS_ERROR("Provide a mode client name in Launch file"); system("rosnode kill rosbuzz_node");}
if(node_handle.getParam("topics/localpos", local_pos_sub_name));
else {ROS_ERROR("Provide a localpos name in YAML file"); system("rosnode kill rosbuzz_node");}
@ -250,8 +251,7 @@ namespace rosbzz_node{
stream_client = n_c.serviceClient<mavros_msgs::StreamRate>(stream_client_name); stream_client = n_c.serviceClient<mavros_msgs::StreamRate>(stream_client_name);
users_sub = n_c.subscribe("users_pos", 1000, &roscontroller::users_pos,this); users_sub = n_c.subscribe("users_pos", 1000, &roscontroller::users_pos,this);
local_pos_sub = n_c.subscribe(local_pos_sub_name, 1000, &roscontroller::local_pos_callback, this);
local_pos_sub = n_c.subscribe("/mavros/local_position/pose", 1000, &roscontroller::local_pos_callback, this);
multi_msg=true; multi_msg=true;
} }