diff --git a/include/roscontroller.h b/include/roscontroller.h index 2892094..626b202 100644 --- a/include/roscontroller.h +++ b/include/roscontroller.h @@ -53,6 +53,7 @@ private: //int oldcmdID=0; int rc_cmd; int barrier; + int message_number=0; std::string bzzfile_name, fcclient_name, armclient, modeclient, rcservice_name,bcfname,dbgfname,out_payload,in_payload,stand_by; bool rcclient; bool multi_msg; diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index 3893072..600fea5 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -68,36 +68,26 @@ namespace rosbzz_node{ //std::cout<<"long obt"<bcode, dbgfname.c_str(), *(size_t*)((get_updater())->bcode_size)); - set_read_update_status(); - mavros_msgs::Mavlink stop_req_packet; - stop_req_packet.payload64.push_back((uint64_t) XBEE_STOP_TRANSMISSION); - payload_pub.publish(stop_req_packet); - std::cout << "request xbee to stop multi-packet transmission" << std::endl; - } + + /*Step buzz script */ buzz_utility::buzz_script_step(); /*Prepare messages and publish them in respective topic*/ - //fprintf(stdout, "before publish msg\n"); + prepare_msg_and_publish(); + /*Set multi message available after update*/ + if(get_update_status()){ + set_read_update_status(); + multi_msg=true; + } /*run once*/ ros::spinOnce(); /*loop rate of ros*/ - /*if( get_update_mode() == CODE_STANDBY){ ros::Rate loop_rate(10); loop_rate.sleep(); - } - else{*/ - ros::Rate loop_rate(10); - loop_rate.sleep(); - //} /*sleep for the mentioned loop rate*/ - timer_step+=1; maintain_pos(timer_step); @@ -126,7 +116,8 @@ namespace rosbzz_node{ } else{ROS_ERROR("Provide a rc client option: yes or no in Launch file"); system("rosnode kill rosbuzz_node");} /*Obtain robot_id from parameter server*/ - n_c.getParam("robot_id", robot_id); + //n_c.getParam("robot_id", robot_id); + robot_id=(int)buzz_utility::get_robotid(); /*Obtain out payload name*/ n_c.getParam("out_payload", out_payload); /*Obtain in payload name*/ @@ -318,6 +309,13 @@ namespace rosbzz_node{ cout<<" [Debug:] sent message "<