Browse Source

Added minor fixes to simulation and parameter view

QGC4.4
lm 15 years ago
parent
commit
d680d7d0ed
  1. 8
      src/comm/MAVLinkSimulationLink.cc
  2. 4
      src/uas/UAS.cc
  3. 3
      src/ui/QGCParamWidget.cc

8
src/comm/MAVLinkSimulationLink.cc

@ -620,6 +620,14 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) @@ -620,6 +620,14 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
{
onboardParams.remove(key);
onboardParams.insert(key, set.param_value);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)key.toStdString().c_str(), set.param_value);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer+=bufferlength;
}
}
}

4
src/uas/UAS.cc

@ -631,8 +631,8 @@ void UAS::setParameter(int component, QString id, float value) @@ -631,8 +631,8 @@ void UAS::setParameter(int component, QString id, float value)
mavlink_message_t msg;
mavlink_param_set_t p;
p.param_value = value;
p.target_system = uasId;
p.target_component = component;
p.target_system = (uint8_t)uasId;
p.target_component = (uint8_t)component;
// Copy string into buffer, ensuring not to exceed the buffer size
char* s = (char*)id.toStdString().c_str();

3
src/ui/QGCParamWidget.cc

@ -153,8 +153,9 @@ void QGCParamWidget::setParameters() @@ -153,8 +153,9 @@ void QGCParamWidget::setParameters()
}
}
}
clear();
//mav->requestParameters();
qDebug() << __FILE__ << __LINE__ << "SETTING ALL PARAMETERS";
requestParameterList();
}
void QGCParamWidget::writeParameters()

Loading…
Cancel
Save