Browse Source

POSIX: Fixed remaining broke gtests

The addition of the hrt workqueue required adding some additional files to
unittests/CMakeLists.txt

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
sbg
Mark Charlebois 10 years ago
parent
commit
fb402bc096
  1. 1
      src/modules/uORB/uORBCommunicator.hpp
  2. 8
      src/platforms/posix/px4_layer/hrt_work.h
  3. 3
      unittests/CMakeLists.txt
  4. 10
      unittests/sbus2_test.cpp
  5. 20
      unittests/uorb_unittests/uORBCommunicatorMock.cpp
  6. 9
      unittests/uorb_unittests/uORBCommunicatorMock.hpp
  7. 22
      unittests/uorb_unittests/uORBCommunicatorMockLoopback.cpp
  8. 7
      unittests/uorb_unittests/uORBCommunicatorMockLoopback.hpp

1
src/modules/uORB/uORBCommunicator.hpp

@ -35,7 +35,6 @@ @@ -35,7 +35,6 @@
#define _uORBCommunicator_hpp_
#include <stdint.h>
#include <string>
namespace uORBCommunicator
{

8
src/platforms/posix/px4_layer/hrt_work.h

@ -46,16 +46,16 @@ void hrt_work_queue_init(void); @@ -46,16 +46,16 @@ void hrt_work_queue_init(void);
int hrt_work_queue(struct work_s *work, worker_t worker, void *arg, uint32_t delay);
void hrt_work_cancel(struct work_s *work);
inline void hrt_work_lock(void);
inline void hrt_work_unlock(void);
//inline void hrt_work_lock(void);
//inline void hrt_work_unlock(void);
inline void hrt_work_lock()
static inline void hrt_work_lock()
{
//PX4_INFO("hrt_work_lock");
sem_wait(&_hrt_work_lock);
}
inline void hrt_work_unlock()
static inline void hrt_work_unlock()
{
//PX4_INFO("hrt_work_unlock");
sem_post(&_hrt_work_lock);

3
unittests/CMakeLists.txt

@ -74,6 +74,7 @@ add_library( px4_platform @@ -74,6 +74,7 @@ add_library( px4_platform
${PX_SRC}/platforms/posix/px4_layer/px4_posix_impl.cpp
${PX_SRC}/platforms/posix/px4_layer/px4_posix_tasks.cpp
${PX_SRC}/platforms/posix/px4_layer/work_lock.c
${PX_SRC}/platforms/posix/px4_layer/hrt_queue.c
${PX_SRC}/platforms/posix/px4_layer/work_queue.c
${PX_SRC}/platforms/posix/px4_layer/dq_rem.c
${PX_SRC}/platforms/posix/px4_layer/sq_addlast.c
@ -81,7 +82,9 @@ add_library( px4_platform @@ -81,7 +82,9 @@ add_library( px4_platform
${PX_SRC}/platforms/posix/px4_layer/sq_addafter.c
${PX_SRC}/platforms/posix/px4_layer/queue.c
${PX_SRC}/platforms/posix/px4_layer/work_cancel.c
${PX_SRC}/platforms/posix/px4_layer/hrt_work_cancel.c
${PX_SRC}/platforms/posix/px4_layer/dq_remfirst.c
${PX_SRC}/platforms/posix/px4_layer/hrt_thread.c
${PX_SRC}/platforms/posix/px4_layer/work_thread.c
${PX_SRC}/platforms/posix/px4_layer/drv_hrt.c
${PX_SRC}/platforms/posix/px4_layer/sq_remfirst.c

10
unittests/sbus2_test.cpp

@ -34,10 +34,10 @@ TEST(SBUS2Test, SBUS2) @@ -34,10 +34,10 @@ TEST(SBUS2Test, SBUS2)
uint8_t frame[30];
unsigned partial_frame_count = 0;
uint16_t rc_values[18];
uint16_t num_values;
bool sbus_failsafe;
bool sbus_frame_drop;
uint16_t max_channels = sizeof(rc_values) / sizeof(rc_values[0]);
//uint16_t num_values;
//bool sbus_failsafe;
//bool sbus_frame_drop;
//uint16_t max_channels = sizeof(rc_values) / sizeof(rc_values[0]);
float last_time = 0;
@ -59,7 +59,7 @@ TEST(SBUS2Test, SBUS2) @@ -59,7 +59,7 @@ TEST(SBUS2Test, SBUS2)
last_time = f;
// Pipe the data into the parser
hrt_abstime now = hrt_absolute_time();
//hrt_abstime now = hrt_absolute_time();
//if (partial_frame_count % 25 == 0)
//sbus_parse(now, frame, &partial_frame_count, rc_values, &num_values, &sbus_failsafe, &sbus_frame_drop, max_channels);

20
unittests/uorb_unittests/uORBCommunicatorMock.cpp

@ -50,13 +50,13 @@ uORB_test::uORBCommunicatorMock::uORBCommunicatorMock() @@ -50,13 +50,13 @@ uORB_test::uORBCommunicatorMock::uORBCommunicatorMock()
int16_t uORB_test::uORBCommunicatorMock::add_subscription
(
const std::string& messageName,
const char * messageName,
int32_t msgRateInHz
)
{
int16_t rc = 0;
PX4_INFO( "got add_subscription for msg[%s] rate[%d]", messageName.c_str(), msgRateInHz );
PX4_INFO( "got add_subscription for msg[%s] rate[%d]", messageName, msgRateInHz );
_msgCounters[messageName]._add_subscriptionCount++;
/*
@ -78,11 +78,11 @@ int16_t uORB_test::uORBCommunicatorMock::add_subscription @@ -78,11 +78,11 @@ int16_t uORB_test::uORBCommunicatorMock::add_subscription
int16_t uORB_test::uORBCommunicatorMock::remove_subscription
(
const std::string& messageName
const char * messageName
)
{
int16_t rc = 0;
PX4_INFO( "got remove_subscription for msg[%s]", messageName.c_str() );
PX4_INFO( "got remove_subscription for msg[%s]", messageName );
_msgCounters[messageName]._remove_subscriptionCount++;
/*
int16_t rc = -1;
@ -113,27 +113,27 @@ int16_t uORB_test::uORBCommunicatorMock::register_handler @@ -113,27 +113,27 @@ int16_t uORB_test::uORBCommunicatorMock::register_handler
int16_t uORB_test::uORBCommunicatorMock::send_message
(
const std::string& messageName,
const char * messageName,
int32_t length,
uint8_t* data
)
{
int16_t rc = 0;
PX4_INFO( "send_message for msg[%s] datalen[%d]", messageName.c_str(), length );
PX4_INFO( "send_message for msg[%s] datalen[%d]", messageName, length );
if( uORB::Manager::get_instance()->is_remote_subscriber_present( messageName ) )
{
_msgCounters[messageName]._send_messageCount++;
if( messageName == "topicA" )
if( strcmp(messageName, "topicA") == 0 )
{
memcpy( &_topicAData, (void*)data, length );
}
else if( messageName == "topicB" )
else if( strcmp(messageName, "topicB") == 0 )
{
memcpy( &_topicBData, (void*)data, length );
}
else
{
//EPRINTF( "error messageName[%s] is not supported", messageName.c_str() );
//EPRINTF( "error messageName[%s] is not supported", messageName );
}
}
/*
@ -200,7 +200,7 @@ void uORB_test::uORBCommunicatorMock::reset_counters() @@ -200,7 +200,7 @@ void uORB_test::uORBCommunicatorMock::reset_counters()
}
}
uORB_test::uORBCommunicatorMock::InterfaceCounters uORB_test::uORBCommunicatorMock::get_interface_counters(const std::string& messageName )
uORB_test::uORBCommunicatorMock::InterfaceCounters uORB_test::uORBCommunicatorMock::get_interface_counters(const char * messageName )
{
return _msgCounters[ messageName ];
}

9
unittests/uorb_unittests/uORBCommunicatorMock.hpp

@ -36,6 +36,7 @@ @@ -36,6 +36,7 @@
#include "uORB/uORBCommunicator.hpp"
#include "uORBGtestTopics.hpp"
#include <map>
#include <string>
#include <set>
namespace uORB_test
@ -72,7 +73,7 @@ class uORB_test::uORBCommunicatorMock : public uORBCommunicator::IChannel @@ -72,7 +73,7 @@ class uORB_test::uORBCommunicatorMock : public uORBCommunicator::IChannel
* Note: This does not mean that the receiver as received it.
* otherwise = failure.
*/
virtual int16_t add_subscription( const std::string& messageName, int32_t msgRateInHz );
virtual int16_t add_subscription( const char *messageName, int32_t msgRateInHz );
/**
@ -86,7 +87,7 @@ class uORB_test::uORBCommunicatorMock : public uORBCommunicator::IChannel @@ -86,7 +87,7 @@ class uORB_test::uORBCommunicatorMock : public uORBCommunicator::IChannel
* Note: This does not necessarily mean that the receiver as received it.
* otherwise = failure.
*/
virtual int16_t remove_subscription( const std::string& messageName );
virtual int16_t remove_subscription( const char * messageName );
/**
* Register Message Handler. This is internal for the IChannel implementer*
@ -108,7 +109,7 @@ class uORB_test::uORBCommunicatorMock : public uORBCommunicator::IChannel @@ -108,7 +109,7 @@ class uORB_test::uORBCommunicatorMock : public uORBCommunicator::IChannel
* Note: This does not mean that the receiver as received it.
* otherwise = failure.
*/
virtual int16_t send_message( const std::string& messageName, int32_t length, uint8_t* data);
virtual int16_t send_message( const char * messageName, int32_t length, uint8_t* data);
uORBCommunicator::IChannelRxHandler* get_rx_handler()
{
@ -120,7 +121,7 @@ class uORB_test::uORBCommunicatorMock : public uORBCommunicator::IChannel @@ -120,7 +121,7 @@ class uORB_test::uORBCommunicatorMock : public uORBCommunicator::IChannel
void reset_counters();
InterfaceCounters get_interface_counters( const std::string& messageName );
InterfaceCounters get_interface_counters( const char * messageName );
private:

22
unittests/uorb_unittests/uORBCommunicatorMockLoopback.cpp

@ -50,13 +50,13 @@ uORB_test::uORBCommunicatorMockLoopback::uORBCommunicatorMockLoopback() @@ -50,13 +50,13 @@ uORB_test::uORBCommunicatorMockLoopback::uORBCommunicatorMockLoopback()
int16_t uORB_test::uORBCommunicatorMockLoopback::add_subscription
(
const std::string& messageName,
const char * messageName,
int32_t msgRateInHz
)
{
int16_t rc = -1;
PX4_INFO( "got add_subscription for msg[%s] rate[%d]", messageName.c_str(), msgRateInHz );
PX4_INFO( "got add_subscription for msg[%s] rate[%d]", messageName, msgRateInHz );
if( _rx_handler )
{
@ -64,7 +64,7 @@ int16_t uORB_test::uORBCommunicatorMockLoopback::add_subscription @@ -64,7 +64,7 @@ int16_t uORB_test::uORBCommunicatorMockLoopback::add_subscription
{
rc = _rx_handler->process_add_subscription
(
_topic_translation_map[messageName],
_topic_translation_map[messageName].c_str(),
msgRateInHz
);
}
@ -74,18 +74,18 @@ int16_t uORB_test::uORBCommunicatorMockLoopback::add_subscription @@ -74,18 +74,18 @@ int16_t uORB_test::uORBCommunicatorMockLoopback::add_subscription
int16_t uORB_test::uORBCommunicatorMockLoopback::remove_subscription
(
const std::string& messageName
const char * messageName
)
{
int16_t rc = -1;
PX4_INFO( "got remove_subscription for msg[%s]", messageName.c_str() );
PX4_INFO( "got remove_subscription for msg[%s]", messageName );
if( _rx_handler )
{
if( _topic_translation_map.find( messageName ) != _topic_translation_map.end() )
{
rc = _rx_handler->process_remove_subscription
(
_topic_translation_map[messageName]
_topic_translation_map[messageName].c_str()
);
}
}
@ -105,22 +105,22 @@ int16_t uORB_test::uORBCommunicatorMockLoopback::register_handler @@ -105,22 +105,22 @@ int16_t uORB_test::uORBCommunicatorMockLoopback::register_handler
int16_t uORB_test::uORBCommunicatorMockLoopback::send_message
(
const std::string& messageName,
const char * messageName,
int32_t length,
uint8_t* data
)
{
int16_t rc = -1;
PX4_INFO( "send_message for msg[%s] datalen[%d]", messageName.c_str(), length );
PX4_INFO( "send_message for msg[%s] datalen[%d]", messageName, length );
if( _rx_handler )
{
if( _topic_translation_map.find( messageName ) != _topic_translation_map.end() )
{
if( uORB::Manager::get_instance()->is_remote_subscriber_present( _topic_translation_map[messageName] ) )
if( uORB::Manager::get_instance()->is_remote_subscriber_present( _topic_translation_map[messageName].c_str() ) )
{
rc = _rx_handler->process_received_message
( _topic_translation_map[messageName], length, data );
PX4_INFO( "[uORBCommunicatorMockLoopback::send_message] return from[topic(%s)] _rx_handler->process_received_message[%d]", messageName.c_str(), rc );
( _topic_translation_map[messageName].c_str(), length, data );
PX4_INFO( "[uORBCommunicatorMockLoopback::send_message] return from[topic(%s)] _rx_handler->process_received_message[%d]", messageName, rc );
}
else
{

7
unittests/uorb_unittests/uORBCommunicatorMockLoopback.hpp

@ -32,6 +32,7 @@ @@ -32,6 +32,7 @@
#include "uORB/uORBCommunicator.hpp"
#include "uORBGtestTopics.hpp"
#include <map>
#include <string>
#include <set>
namespace uORB_test
@ -59,7 +60,7 @@ class uORB_test::uORBCommunicatorMockLoopback : public uORBCommunicator::IChanne @@ -59,7 +60,7 @@ class uORB_test::uORBCommunicatorMockLoopback : public uORBCommunicator::IChanne
* Note: This does not mean that the receiver as received it.
* otherwise = failure.
*/
virtual int16_t add_subscription( const std::string& messageName, int32_t msgRateInHz );
virtual int16_t add_subscription( const char * messageName, int32_t msgRateInHz );
/**
@ -73,7 +74,7 @@ class uORB_test::uORBCommunicatorMockLoopback : public uORBCommunicator::IChanne @@ -73,7 +74,7 @@ class uORB_test::uORBCommunicatorMockLoopback : public uORBCommunicator::IChanne
* Note: This does not necessarily mean that the receiver as received it.
* otherwise = failure.
*/
virtual int16_t remove_subscription( const std::string& messageName );
virtual int16_t remove_subscription( const char * messageName );
/**
* Register Message Handler. This is internal for the IChannel implementer*
@ -95,7 +96,7 @@ class uORB_test::uORBCommunicatorMockLoopback : public uORBCommunicator::IChanne @@ -95,7 +96,7 @@ class uORB_test::uORBCommunicatorMockLoopback : public uORBCommunicator::IChanne
* Note: This does not mean that the receiver as received it.
* otherwise = failure.
*/
virtual int16_t send_message( const std::string& messageName, int32_t length, uint8_t* data);
virtual int16_t send_message( const char * messageName, int32_t length, uint8_t* data);
uORBCommunicator::IChannelRxHandler* get_rx_handler()
{

Loading…
Cancel
Save