def __init__(self, target_sys, target_comp): # initiate variables self.stop = False self.first_msg_ok = False self.request_sent = False self.mission_count = 0 self.mission_id_next = 0 self.mi = mission_lib() self.sys_id = 0 # reset when receiving first msg self.comp_id = 0 self.mission_list = mavlink_lora_mission_list() self.download_timer = None self.retries = 0 # initiate node rospy.init_node(ros_node_name) self.mission_list_pub = rospy.Publisher("/telemetry/new_mission", mavlink_lora_mission_list, queue_size=0) self.mavlink_msg_pub = rospy.Publisher(mavlink_lora_tx_pub, mavlink_lora_msg, queue_size=0) rospy.Subscriber(mavlink_lora_rx_sub, mavlink_lora_msg, self.on_mavlink_msg) self.rate = rospy.Rate(ros_node_update_interval) # wait until everything is running (important) rospy.sleep(1)
def __init__(self): # initiate variables self.stop = False self.first_msg_ok = False self.request_sent = False self.busy = False self.mission_count = 0 self.mission_id_next = 0 self.mi = mission_lib() self.sys_id = 0 # reset when receiving first msg self.comp_id = 0 self.active_mission_item = 0 self.active_mission_length = 0 self.mission_list_down = mavlink_lora_mission_list() self.mission_list_up = mavlink_lora_mission_list() self.active_mission = mavlink_lora_mission_list( waypoints=[mavlink_lora_mission_item_int()]) # self.active_mission.waypoints.append(mavlink_lora_mission_item_int()) rospack = rospkg.RosPack() package_path = rospack.get_path("telemetry") self.plan_path = package_path + "/plans/" self.download_timer = None self.retries = 0 # Topic handlers self.mavlink_msg_pub = rospy.Publisher("/mavlink_tx", mavlink_lora_msg, queue_size=0) self.mission_upload_pub = rospy.Publisher( "/mavlink_interface/mission/mavlink_upload_mission", mavlink_lora_mission_list, queue_size=0) self.mission_info_pub = rospy.Publisher("/telemetry/mission_info", telemetry_mission_info, queue_size=0)
def __init__(self, mission_id_set): # save variables self.mission_id_set = mission_id_set # initiate variables self.stop = False self.first_msg_ok = False self.request_sent = False self.mi = mission_lib() self.sys_id = 0 # reset when receiving first msg self.comp_id = 0 # initiate node rospy.init_node(ros_node_name) self.mavlink_msg_pub = rospy.Publisher(mavlink_lora_tx_pub, mavlink_lora_msg, queue_size=0) rospy.Subscriber(mavlink_lora_rx_sub, mavlink_lora_msg, self.on_mavlink_msg) self.rate = rospy.Rate(ros_node_update_interval) # wait until everything is running (important) rospy.sleep(1)