static int do_show_index(const char *index, bool used_index) { char *end; int i = strtol(index, &end, 10); param_t param; int32_t ii; float ff; if (used_index) { param = param_for_used_index(i); } else { param = param_for_index(i); } if (param == PARAM_INVALID) { PX4_ERR("param not found for index %u", i); return 1; } PARAM_PRINT("index %d: %c %c %s [%d,%d] : ", i, (param_used(param) ? 'x' : ' '), param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), param_name(param), param_get_used_index(param), param_get_index(param)); switch (param_type(param)) { case PARAM_TYPE_INT32: if (!param_get(param, &ii)) { PARAM_PRINT("%ld\n", (long)ii); } break; case PARAM_TYPE_FLOAT: if (!param_get(param, &ff)) { PARAM_PRINT("%4.4f\n", (double)ff); } break; default: PARAM_PRINT("<unknown type %d>\n", 0 + param_type(param)); } return 0; }
void MavlinkParametersManager::handle_message(const mavlink_message_t *msg) { switch (msg->msgid) { case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { /* request all parameters */ mavlink_param_request_list_t req_list; mavlink_msg_param_request_list_decode(msg, &req_list); if (req_list.target_system == mavlink_system.sysid && (req_list.target_component == mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) { if (_send_all_index < 0) { _send_all_index = PARAM_HASH; } else { /* a restart should skip the hash check on the ground */ _send_all_index = 0; } } if (req_list.target_system == mavlink_system.sysid && req_list.target_component < 127 && (req_list.target_component != mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) { // publish list request to UAVCAN driver via uORB. uavcan_parameter_request_s req; req.message_type = msg->msgid; req.node_id = req_list.target_component; req.param_index = 0; if (_uavcan_parameter_request_pub == nullptr) { _uavcan_parameter_request_pub = orb_advertise(ORB_ID(uavcan_parameter_request), &req); } else { orb_publish(ORB_ID(uavcan_parameter_request), _uavcan_parameter_request_pub, &req); } } break; } case MAVLINK_MSG_ID_PARAM_SET: { /* set parameter */ mavlink_param_set_t set; mavlink_msg_param_set_decode(msg, &set); if (set.target_system == mavlink_system.sysid && (set.target_component == mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) { /* local name buffer to enforce null-terminated string */ char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; strncpy(name, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; /* Whatever the value is, we're being told to stop sending */ if (strncmp(name, "_HASH_CHECK", sizeof(name)) == 0) { _send_all_index = -1; /* No other action taken, return */ return; } /* attempt to find parameter, set and send it */ param_t param = param_find_no_notification(name); if (param == PARAM_INVALID) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] unknown param: %s", name); _mavlink->send_statustext_info(buf); } else { // Load current value before setting it float curr_val; param_get(param, &curr_val); param_set(param, &(set.param_value)); // Check if the parameter changed. If it didn't change, send current value back if (!(fabsf(curr_val - set.param_value) > 0.0f)) { send_param(param); } } } if (set.target_system == mavlink_system.sysid && set.target_component < 127 && (set.target_component != mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) { // publish set request to UAVCAN driver via uORB. uavcan_parameter_request_s req; req.message_type = msg->msgid; req.node_id = set.target_component; req.param_index = -1; strncpy(req.param_id, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1); req.param_id[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; if (set.param_type == MAV_PARAM_TYPE_REAL32) { req.param_type = MAV_PARAM_TYPE_REAL32; req.real_value = set.param_value; } else { int32_t val; memcpy(&val, &set.param_value, sizeof(int32_t)); req.param_type = MAV_PARAM_TYPE_INT64; req.int_value = val; } if (_uavcan_parameter_request_pub == nullptr) { _uavcan_parameter_request_pub = orb_advertise(ORB_ID(uavcan_parameter_request), &req); } else { orb_publish(ORB_ID(uavcan_parameter_request), _uavcan_parameter_request_pub, &req); } } break; } case MAVLINK_MSG_ID_PARAM_REQUEST_READ: { /* request one parameter */ mavlink_param_request_read_t req_read; mavlink_msg_param_request_read_decode(msg, &req_read); if (req_read.target_system == mavlink_system.sysid && (req_read.target_component == mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) { /* when no index is given, loop through string ids and compare them */ if (req_read.param_index < 0) { /* XXX: I left this in so older versions of QGC wouldn't break */ if (strncmp(req_read.param_id, HASH_PARAM, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN) == 0) { /* return hash check for cached params */ uint32_t hash = param_hash_check(); /* build the one-off response message */ mavlink_param_value_t param_value; param_value.param_count = param_count_used(); param_value.param_index = -1; strncpy(param_value.param_id, HASH_PARAM, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); param_value.param_type = MAV_PARAM_TYPE_UINT32; memcpy(¶m_value.param_value, &hash, sizeof(hash)); mavlink_msg_param_value_send_struct(_mavlink->get_channel(), ¶m_value); } else { /* local name buffer to enforce null-terminated string */ char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; strncpy(name, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; /* attempt to find parameter and send it */ send_param(param_find_no_notification(name)); } } else { /* when index is >= 0, send this parameter again */ int ret = send_param(param_for_used_index(req_read.param_index)); if (ret == 1) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] unknown param ID: %u", req_read.param_index); _mavlink->send_statustext_info(buf); } else if (ret == 2) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] failed loading param from storage ID: %u", req_read.param_index); _mavlink->send_statustext_info(buf); } } } if (req_read.target_system == mavlink_system.sysid && req_read.target_component < 127 && (req_read.target_component != mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) { // publish set request to UAVCAN driver via uORB. uavcan_parameter_request_s req = {}; req.timestamp = hrt_absolute_time(); req.message_type = msg->msgid; req.node_id = req_read.target_component; req.param_index = req_read.param_index; strncpy(req.param_id, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1); req.param_id[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; // Enque the request and forward the first to the uavcan node enque_uavcan_request(&req); request_next_uavcan_parameter(); } break; } case MAVLINK_MSG_ID_PARAM_MAP_RC: { /* map a rc channel to a parameter */ mavlink_param_map_rc_t map_rc; mavlink_msg_param_map_rc_decode(msg, &map_rc); if (map_rc.target_system == mavlink_system.sysid && (map_rc.target_component == mavlink_system.compid || map_rc.target_component == MAV_COMP_ID_ALL)) { /* Copy values from msg to uorb using the parameter_rc_channel_index as index */ size_t i = map_rc.parameter_rc_channel_index; _rc_param_map.param_index[i] = map_rc.param_index; strncpy(&(_rc_param_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1)]), map_rc.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ _rc_param_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1) + rc_parameter_map_s::PARAM_ID_LEN] = '\0'; _rc_param_map.scale[i] = map_rc.scale; _rc_param_map.value0[i] = map_rc.param_value0; _rc_param_map.value_min[i] = map_rc.param_value_min; _rc_param_map.value_max[i] = map_rc.param_value_max; if (map_rc.param_index == -2) { // -2 means unset map _rc_param_map.valid[i] = false; } else { _rc_param_map.valid[i] = true; } _rc_param_map.timestamp = hrt_absolute_time(); if (_rc_param_map_pub == nullptr) { _rc_param_map_pub = orb_advertise(ORB_ID(rc_parameter_map), &_rc_param_map); } else { orb_publish(ORB_ID(rc_parameter_map), _rc_param_map_pub, &_rc_param_map); } } break; } default: break; } }
void MavlinkParametersManager::handle_message(const mavlink_message_t *msg) { switch (msg->msgid) { case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { /* request all parameters */ mavlink_param_request_list_t req_list; mavlink_msg_param_request_list_decode(msg, &req_list); if (req_list.target_system == mavlink_system.sysid && (req_list.target_component == mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) { _send_all_index = 0; } break; } case MAVLINK_MSG_ID_PARAM_SET: { /* set parameter */ if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) { mavlink_param_set_t set; mavlink_msg_param_set_decode(msg, &set); if (set.target_system == mavlink_system.sysid && (set.target_component == mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) { /* local name buffer to enforce null-terminated string */ char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; strncpy(name, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; /* attempt to find parameter, set and send it */ param_t param = param_find_no_notification(name); if (param == PARAM_INVALID) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] unknown param: %s", name); _mavlink->send_statustext_info(buf); } else { /* set and send parameter */ param_set(param, &(set.param_value)); send_param(param); } } } break; } case MAVLINK_MSG_ID_PARAM_REQUEST_READ: { /* request one parameter */ mavlink_param_request_read_t req_read; mavlink_msg_param_request_read_decode(msg, &req_read); if (req_read.target_system == mavlink_system.sysid && (req_read.target_component == mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) { /* when no index is given, loop through string ids and compare them */ if (req_read.param_index < 0) { /* local name buffer to enforce null-terminated string */ char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; strncpy(name, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; /* attempt to find parameter and send it */ send_param(param_find_no_notification(name)); } else { /* when index is >= 0, send this parameter again */ send_param(param_for_used_index(req_read.param_index)); } } break; } case MAVLINK_MSG_ID_PARAM_MAP_RC: { /* map a rc channel to a parameter */ mavlink_param_map_rc_t map_rc; mavlink_msg_param_map_rc_decode(msg, &map_rc); if (map_rc.target_system == mavlink_system.sysid && (map_rc.target_component == mavlink_system.compid || map_rc.target_component == MAV_COMP_ID_ALL)) { /* Copy values from msg to uorb using the parameter_rc_channel_index as index */ size_t i = map_rc.parameter_rc_channel_index; _rc_param_map.param_index[i] = map_rc.param_index; strncpy(&(_rc_param_map.param_id[i][0]), map_rc.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ _rc_param_map.param_id[i][MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = '\0'; _rc_param_map.scale[i] = map_rc.scale; _rc_param_map.value0[i] = map_rc.param_value0; _rc_param_map.value_min[i] = map_rc.param_value_min; _rc_param_map.value_max[i] = map_rc.param_value_max; if (map_rc.param_index == -2) { // -2 means unset map _rc_param_map.valid[i] = false; } else { _rc_param_map.valid[i] = true; } _rc_param_map.timestamp = hrt_absolute_time(); if (_rc_param_map_pub < 0) { _rc_param_map_pub = orb_advertise(ORB_ID(rc_parameter_map), &_rc_param_map); } else { orb_publish(ORB_ID(rc_parameter_map), _rc_param_map_pub, &_rc_param_map); } } break; } default: break; } }