mavlink: fixed parameter string handling

this prevents running past the end of a non-terminated string.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1740 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-03-03 11:40:19 +00:00
parent b7be7bc41a
commit c9f6e12d60
1 changed files with 7 additions and 8 deletions

View File

@ -551,7 +551,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
// set parameter
const char * key = (const char*) packet.param_id;
char key[ONBOARD_PARAM_NAME_LENGTH+1];
strncpy(key, (char *)packet.param_id, ONBOARD_PARAM_NAME_LENGTH);
key[ONBOARD_PARAM_NAME_LENGTH] = 0;
// find the requested parameter
vp = AP_Var::find(key);
@ -581,13 +584,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
// Report back new value
char param_name[ONBOARD_PARAM_NAME_LENGTH]; // XXX HACK - need something to return a char *
vp->copy_name(param_name, sizeof(param_name));
mavlink_msg_param_value_send(chan,
(int8_t*)param_name,
packet.param_value,
_count_parameters(),
-1); // XXX we don't actually know what its index is...
mavlink_msg_param_value_send(chan, (int8_t *)key, packet.param_value,
_count_parameters(),
-1); // XXX we don't actually know what its index is...
break;
} // end case