out and in message change in implementation correction
This commit is contained in:
parent
9e9eb964b1
commit
df484609ea
|
@ -9,7 +9,7 @@ endif()
|
||||||
find_package(catkin REQUIRED COMPONENTS
|
find_package(catkin REQUIRED COMPONENTS
|
||||||
roscpp
|
roscpp
|
||||||
std_msgs
|
std_msgs
|
||||||
#mavros_msgs
|
mavros_msgs
|
||||||
sensor_msgs
|
sensor_msgs
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
|
@ -80,7 +80,7 @@ namespace buzz_utility{
|
||||||
tot += sizeof(uint16_t);
|
tot += sizeof(uint16_t);
|
||||||
/* Append message to the Buzz input message queue */
|
/* Append message to the Buzz input message queue */
|
||||||
if(unMsgSize > 0 && unMsgSize <= size - tot ) {
|
if(unMsgSize > 0 && unMsgSize <= size - tot ) {
|
||||||
buzzinmsg_queue_append(VM->inmsgs,
|
buzzinmsg_queue_append(VM,
|
||||||
buzzmsg_payload_frombuffer(pl +tot, unMsgSize));
|
buzzmsg_payload_frombuffer(pl +tot, unMsgSize));
|
||||||
tot += unMsgSize;
|
tot += unMsgSize;
|
||||||
}
|
}
|
||||||
|
@ -104,9 +104,9 @@ namespace buzz_utility{
|
||||||
/* Send messages from FIFO */
|
/* Send messages from FIFO */
|
||||||
do {
|
do {
|
||||||
/* Are there more messages? */
|
/* Are there more messages? */
|
||||||
if(buzzoutmsg_queue_isempty(VM->outmsgs)) break;
|
if(buzzoutmsg_queue_isempty(VM)) break;
|
||||||
/* Get first message */
|
/* Get first message */
|
||||||
buzzmsg_payload_t m = buzzoutmsg_queue_first(VM->outmsgs);
|
buzzmsg_payload_t m = buzzoutmsg_queue_first(VM);
|
||||||
/* Make sure the next message fits the data buffer */
|
/* Make sure the next message fits the data buffer */
|
||||||
if(tot + buzzmsg_payload_size(m) + sizeof(uint16_t)
|
if(tot + buzzmsg_payload_size(m) + sizeof(uint16_t)
|
||||||
>
|
>
|
||||||
|
@ -124,7 +124,7 @@ namespace buzz_utility{
|
||||||
tot += buzzmsg_payload_size(m);
|
tot += buzzmsg_payload_size(m);
|
||||||
|
|
||||||
/* Get rid of message */
|
/* Get rid of message */
|
||||||
buzzoutmsg_queue_next(VM->outmsgs);
|
buzzoutmsg_queue_next(VM);
|
||||||
buzzmsg_payload_destroy(&m);
|
buzzmsg_payload_destroy(&m);
|
||||||
} while(1);
|
} while(1);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue