setpoint launch

This commit is contained in:
David St-Onge 2017-04-05 18:11:27 -04:00
parent 7c5340cdd6
commit 6fb86e7dd0
4 changed files with 6 additions and 2 deletions

View File

@ -76,7 +76,7 @@ private:
/*tmp to be corrected*/
uint8_t no_cnt=0;
uint8_t old_val=0;
std::string bzzfile_name, fcclient_name, armclient, modeclient, rcservice_name,bcfname,dbgfname,out_payload,in_payload,stand_by,xbeesrv_name;
std::string bzzfile_name, fcclient_name, armclient, modeclient, rcservice_name,bcfname,dbgfname,out_payload,in_payload,stand_by,xbeesrv_name, setpoint_name;
std::string stream_client_name;
std::string relative_altitude_sub_name;
bool rcclient;

View File

@ -3,6 +3,7 @@ topics:
battery : /power_status
status : /flight_status
fcclient : /dji_mavcmd
setpoint : /setpoint_raw/local
armclient: /dji_mavarm
modeclient: /dji_mavmode
altitude: /rel_alt

View File

@ -3,6 +3,7 @@ topics:
battery : /mavros/battery
status : /mavros/state
fcclient: /mavros/cmd/command
setpoint: /mavros/setpoint_raw/local
armclient: /mavros/cmd/arming
modeclient: /mavros/set_mode
stream: /mavros/set_stream_rate

View File

@ -170,6 +170,8 @@ namespace rosbzz_node{
/*Obtain fc client name from parameter server*/
if(node_handle.getParam("topics/fcclient", fcclient_name));
else {ROS_ERROR("Provide a fc client name in Launch file"); system("rosnode kill rosbuzz_node");}
if(node_handle.getParam("topics/setpoint", setpoint_name));
else {ROS_ERROR("Provide a Set Point name in Launch file"); system("rosnode kill rosbuzz_node");}
if(node_handle.getParam("topics/armclient", armclient));
else {ROS_ERROR("Provide an arm client name in Launch file"); system("rosnode kill rosbuzz_node");}
if(node_handle.getParam("topics/modeclient", modeclient));
@ -195,7 +197,7 @@ namespace rosbzz_node{
/*publishers*/
payload_pub = n_c.advertise<mavros_msgs::Mavlink>(out_payload, 1000);
neigh_pos_pub = n_c.advertise<rosbuzz::neigh_pos>("/neighbours_pos",1000);
localsetpoint_pub = n_c.advertise<mavros_msgs::PositionTarget>("/mavros/setpoint_raw/local",1000);
localsetpoint_pub = n_c.advertise<mavros_msgs::PositionTarget>(setpoint_name,1000);
/* Service Clients*/
arm_client = n_c.serviceClient<mavros_msgs::CommandBool>(armclient);
mode_client = n_c.serviceClient<mavros_msgs::SetMode>(modeclient);