git commit -m "first commit for v2"

This commit is contained in:
2025-12-29 16:21:22 +07:00
commit aa3d832d5c
1807 changed files with 307078 additions and 0 deletions

View File

@@ -0,0 +1,102 @@
// Bring in my package's API, which is what I'm testing
#include <socketcan_interface/delegates.h>
#include <socketcan_interface/dummy.h>
#include <boost/bind.hpp>
// Bring in gtest
#include <gtest/gtest.h>
class Receiver {
public:
std::list<std::string> responses;
void handle(const can::Frame &f){
responses.push_back(can::tostring(f, true));
}
Receiver() = default;
~Receiver() = default;
private:
Receiver(const Receiver&) = delete;
Receiver& operator=(const Receiver&) = delete;
};
Receiver g_r2;
void fill_r2(const can::Frame &f){
g_r2.handle(f);
}
void fill_any(Receiver &r, const can::Frame &f){
r.handle(f);
}
TEST(DelegatesTest, testFrameDelegate)
{
can::DummyBus bus("testFrameDelegate");
can::ThreadedDummyInterface dummy;
dummy.init(bus.name, true, can::NoSettings::create());
Receiver r1, r3, r4, r5;
boost::shared_ptr<Receiver> r6(new Receiver());
std::shared_ptr<Receiver> r7(new Receiver());
can::FrameListenerConstSharedPtr l1 = dummy.createMsgListener(can::CommInterface::FrameDelegate(&r1, &Receiver::handle));
can::FrameListenerConstSharedPtr l2 = dummy.createMsgListener(can::CommInterface::FrameDelegate(fill_r2));
can::FrameListenerConstSharedPtr l3 = dummy.createMsgListener(can::CommInterface::FrameDelegate(std::bind(fill_any, std::ref(r3), std::placeholders::_1)));
can::FrameListenerConstSharedPtr l4 = dummy.createMsgListener(std::bind(fill_any, std::ref(r4), std::placeholders::_1));
can::FrameListenerConstSharedPtr l5 = dummy.createMsgListener(boost::bind(fill_any, boost::ref(r5), boost::placeholders::_1));
can::FrameListenerConstSharedPtr l6 = dummy.createMsgListener(can::CommInterface::FrameDelegate(r6, &Receiver::handle));
can::FrameListenerConstSharedPtr l7 = dummy.createMsgListener(can::CommInterface::FrameDelegate(r7, &Receiver::handle));
std::list<std::string> expected;
dummy.send(can::toframe("0#8200"));
dummy.flush();
expected.push_back("0#8200");
EXPECT_EQ(expected, r1.responses);
EXPECT_EQ(expected, g_r2.responses);
EXPECT_EQ(expected, r3.responses);
EXPECT_EQ(expected, r4.responses);
EXPECT_EQ(expected, r5.responses);
EXPECT_EQ(expected, r6->responses);
EXPECT_EQ(expected, r7->responses);
}
class BoolTest {
bool ret_;
public:
bool test_bool() { return ret_; }
BoolTest(bool ret) : ret_(ret) {}
public:
BoolTest(const BoolTest&) = delete;
BoolTest& operator=(const BoolTest&) = delete;
};
TEST(DelegatesTest, testBoolFunc)
{
using BoolFunc = std::function<bool(void)>;
using BoolDelegate = can::DelegateHelper<BoolFunc>;
BoolDelegate d1([]() { return false; });
BoolDelegate d2([]() { return true; });
EXPECT_FALSE(d1());
EXPECT_TRUE(d2());
BoolTest b1(false);
BoolTest b2(true);
BoolDelegate d3(&b1, &BoolTest::test_bool);
BoolDelegate d4(&b2, &BoolTest::test_bool);
EXPECT_FALSE(d3());
EXPECT_TRUE(d4());
}
// Run all the tests that were declared with TEST()
int main(int argc, char **argv){
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

View File

@@ -0,0 +1,84 @@
// Bring in my package's API, which is what I'm testing
#include <socketcan_interface/dispatcher.h>
// Bring in gtest
#include <gtest/gtest.h>
class Counter {
public:
size_t counter_;
Counter() : counter_(0) {}
void count(const can::Frame &msg) {
++counter_;
}
};
TEST(DispatcherTest, testFilteredDispatcher)
{
can::FilteredDispatcher<unsigned int, can::CommInterface::FrameListener> dispatcher;
Counter counter1;
Counter counter2;
std::vector<can::CommInterface::FrameListenerConstSharedPtr> listeners;
const size_t max_id = (1<<11);
for(size_t i=0; i < max_id; i+=2) {
listeners.push_back(dispatcher.createListener(can::MsgHeader(i), can::CommInterface::FrameDelegate(&counter1, &Counter::count)));
listeners.push_back(dispatcher.createListener(can::MsgHeader(i+1), can::CommInterface::FrameDelegate(&counter2, &Counter::count)));
}
boost::chrono::steady_clock::time_point start = boost::chrono::steady_clock::now();
const size_t num = 1000 * max_id;
for(size_t i=0; i < num; ++i) {
dispatcher.dispatch(can::Frame(can::MsgHeader(i%max_id)));
}
boost::chrono::steady_clock::time_point now = boost::chrono::steady_clock::now();
double diff = boost::chrono::duration_cast<boost::chrono::duration<double> >(now-start).count();
EXPECT_EQ(num, counter1.counter_+ counter2.counter_);
EXPECT_EQ(counter1.counter_, counter2.counter_);
std::cout << std::fixed << diff << "\t" << num << "\t" << num / diff << std::endl;
}
TEST(DispatcherTest, testSimpleDispatcher)
{
can::SimpleDispatcher<can::CommInterface::FrameListener> dispatcher;
Counter counter;
can::CommInterface::FrameListenerConstSharedPtr listener = dispatcher.createListener(can::CommInterface::FrameDelegate(&counter, &Counter::count));
boost::chrono::steady_clock::time_point start = boost::chrono::steady_clock::now();
const size_t max_id = (1<<11);
const size_t num = 1000*max_id;
for(size_t i=0; i < num; ++i) {
dispatcher.dispatch(can::Frame(can::MsgHeader(i%max_id)));
}
boost::chrono::steady_clock::time_point now = boost::chrono::steady_clock::now();
double diff = boost::chrono::duration_cast<boost::chrono::duration<double> >(now-start).count();
EXPECT_EQ(num, counter.counter_);
std::cout << std::fixed << diff << "\t" << num << "\t" << num / diff << std::endl;
}
TEST(DispatcherTest, testDelegateOnly)
{
Counter counter;
can::CommInterface::FrameDelegate delegate(&counter, &Counter::count);
boost::chrono::steady_clock::time_point start = boost::chrono::steady_clock::now();
const size_t max_id = (1<<11);
const size_t num = 10000*max_id;
for(size_t i=0; i < num; ++i) {
delegate(can::Frame(can::MsgHeader(i%max_id)));
}
boost::chrono::steady_clock::time_point now = boost::chrono::steady_clock::now();
double diff = boost::chrono::duration_cast<boost::chrono::duration<double> >(now-start).count();
EXPECT_EQ(num, counter.counter_);
std::cout << std::fixed << diff << "\t" << num << "\t" << num / diff << std::endl;
}
// Run all the tests that were declared with TEST()
int main(int argc, char **argv){
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

View File

@@ -0,0 +1,42 @@
// Bring in my package's API, which is what I'm testing
#include <socketcan_interface/dispatcher.h>
#include <socketcan_interface/dummy.h>
// Bring in gtest
#include <gtest/gtest.h>
// Declare a test
TEST(DummyInterfaceTest, testCase1)
{
can::DummyBus bus("testCase1");
can::ThreadedDummyInterface dummy;
dummy.init(bus.name, true, can::NoSettings::create());
can::DummyReplay replay;
replay.add("0#8200", {"701#00", "701#04"});
replay.init(bus);
std::list<std::string> expected{"0#8200", "701#00", "701#04"};
std::list<std::string> responses;
auto listener = dummy.createMsgListener([&responses](auto& f) {
responses.push_back(can::tostring(f, true));
});
EXPECT_FALSE(replay.done());
dummy.send(can::toframe("0#8200"));
replay.flush();
dummy.flush();
EXPECT_EQ(expected, responses);
EXPECT_TRUE(replay.done());
}
// Run all the tests that were declared with TEST()
int main(int argc, char **argv){
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

View File

@@ -0,0 +1,115 @@
// Bring in my package's API, which is what I'm testing
#include <socketcan_interface/filter.h>
#include <socketcan_interface/string.h>
#include <socketcan_interface/dummy.h>
// Bring in gtest
#include <gtest/gtest.h>
TEST(FilterTest, simpleMask)
{
const std::string msg1("123#");
const std::string msg2("124#");
can::FrameFilterSharedPtr f1 = can::tofilter("123");
EXPECT_TRUE(f1->pass(can::toframe(msg1)));
EXPECT_FALSE(f1->pass(can::toframe(msg2)));
}
TEST(FilterTest, maskTests)
{
const std::string msg1("123#");
const std::string msg2("124#");
const std::string msg3("122#");
can::FrameFilterSharedPtr f1 = can::tofilter("123:123");
can::FrameFilterSharedPtr f2 = can::tofilter("123:ffe");
can::FrameFilterSharedPtr f3 = can::tofilter("123~123");
EXPECT_TRUE(f1->pass(can::toframe(msg1)));
EXPECT_FALSE(f1->pass(can::toframe(msg2)));
EXPECT_FALSE(f1->pass(can::toframe(msg3)));
EXPECT_TRUE(f2->pass(can::toframe(msg1)));
EXPECT_FALSE(f2->pass(can::toframe(msg2)));
EXPECT_TRUE(f2->pass(can::toframe(msg3)));
EXPECT_FALSE(f3->pass(can::toframe(msg1)));
EXPECT_TRUE(f3->pass(can::toframe(msg2)));
EXPECT_TRUE(f3->pass(can::toframe(msg3)));
}
TEST(FilterTest, rangeTest)
{
const std::string msg1("120#");
const std::string msg2("125#");
const std::string msg3("130#");
can::FrameFilterSharedPtr f1 = can::tofilter("120-120");
can::FrameFilterSharedPtr f2 = can::tofilter("120_120");
can::FrameFilterSharedPtr f3 = can::tofilter("120-125");
EXPECT_TRUE(f1->pass(can::toframe(msg1)));
EXPECT_FALSE(f1->pass(can::toframe(msg2)));
EXPECT_FALSE(f1->pass(can::toframe(msg3)));
EXPECT_FALSE(f2->pass(can::toframe(msg1)));
EXPECT_TRUE(f2->pass(can::toframe(msg2)));
EXPECT_TRUE(f2->pass(can::toframe(msg3)));
EXPECT_TRUE(f3->pass(can::toframe(msg1)));
EXPECT_TRUE(f3->pass(can::toframe(msg2)));
EXPECT_FALSE(f3->pass(can::toframe(msg3)));
}
class Counter {
public:
size_t count_;
Counter(): count_(0) {}
void count(const can::Frame &frame) {
++count_;
}
};
TEST(FilterTest, listenerTest)
{
Counter counter;
can::DummyBus bus("listenerTest");
can::ThreadedDummyInterfaceSharedPtr dummy = std::make_shared<can::ThreadedDummyInterface>();
dummy->init(bus.name, true, can::NoSettings::create());
can::FilteredFrameListener::FilterVector filters;
filters.push_back(can::tofilter("123:FFE"));
can::FrameListenerConstSharedPtr listener(new can::FilteredFrameListener(dummy,std::bind(&Counter::count, std::ref(counter), std::placeholders::_1), filters));
can::Frame f1 = can::toframe("123#");
can::Frame f2 = can::toframe("124#");
can::Frame f3 = can::toframe("122#");
dummy->send(f1);
dummy->flush();
EXPECT_EQ(1, counter.count_);
dummy->send(f2);
dummy->flush();
EXPECT_EQ(1, counter.count_);
dummy->send(f3);
dummy->flush();
EXPECT_EQ(2, counter.count_);
}
// Run all the tests that were declared with TEST()
int main(int argc, char **argv){
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

View File

@@ -0,0 +1,91 @@
// Bring in my package's API, which is what I'm testing
#include <socketcan_interface/settings.h>
#include <socketcan_interface/xmlrpc_settings.h>
#include <socketcan_interface/socketcan.h>
// Bring in gtest
#include <gtest/gtest.h>
TEST(SettingTest, socketcan_masks)
{
const can_err_mask_t fatal_errors = ( CAN_ERR_TX_TIMEOUT /* TX timeout (by netdevice driver) */
| CAN_ERR_BUSOFF /* bus off */
| CAN_ERR_BUSERROR /* bus error (may flood!) */
| CAN_ERR_RESTARTED /* controller restarted */
);
const can_err_mask_t report_errors = ( CAN_ERR_LOSTARB /* lost arbitration / data[0] */
| CAN_ERR_CRTL /* controller problems / data[1] */
| CAN_ERR_PROT /* protocol violations / data[2..3] */
| CAN_ERR_TRX /* transceiver status / data[4] */
| CAN_ERR_ACK /* received no ACK on transmission */
);
can::SocketCANInterface sci;
// defaults
sci.init("None", false, can::NoSettings::create());
EXPECT_EQ(sci.getErrorMask(), fatal_errors | report_errors);
EXPECT_EQ(sci.getFatalErrorMask(), fatal_errors);
// remove report-only flag
auto m1 = can::SettingsMap::create();
m1->set("error_mask/CAN_ERR_LOSTARB", false);
sci.init("None", false, m1);
EXPECT_EQ(sci.getErrorMask(), (fatal_errors | report_errors) & (~CAN_ERR_LOSTARB));
EXPECT_EQ(sci.getFatalErrorMask(), fatal_errors);
// cannot remove fatal flag from report only
auto m2 = can::SettingsMap::create();
m2->set("error_mask/CAN_ERR_TX_TIMEOUT", false);
sci.init("None", false, m2);
EXPECT_EQ(sci.getErrorMask(), (fatal_errors | report_errors));
EXPECT_EQ(sci.getFatalErrorMask(), fatal_errors);
// remove fatal flag
auto m3 = can::SettingsMap::create();
m3->set("fatal_error_mask/CAN_ERR_TX_TIMEOUT", false);
sci.init("None", false, m3);
EXPECT_EQ(sci.getErrorMask(), (fatal_errors | report_errors) & (~CAN_ERR_TX_TIMEOUT));
EXPECT_EQ(sci.getFatalErrorMask(), fatal_errors & (~CAN_ERR_TX_TIMEOUT));
// remove fatal and report flag
auto m4 = can::SettingsMap::create();
m4->set("fatal_error_mask/CAN_ERR_TX_TIMEOUT", false);
m4->set("error_mask/CAN_ERR_LOSTARB", false);
sci.init("None", false, m4);
EXPECT_EQ(sci.getErrorMask(), (fatal_errors | report_errors) & ~(CAN_ERR_TX_TIMEOUT|CAN_ERR_LOSTARB));
EXPECT_EQ(sci.getFatalErrorMask(), fatal_errors & (~CAN_ERR_TX_TIMEOUT));
}
TEST(SettingTest, xmlrpc)
{
XmlRpc::XmlRpcValue value;
value["param"] = 1;
XmlRpc::XmlRpcValue segment;
segment["param"] = 2;
value["segment"] = segment;
XmlRpcSettings settings(value);
ASSERT_TRUE(value["segment"].hasMember(std::string("param")));
int res;
EXPECT_TRUE(settings.get<int>("param", res));
EXPECT_EQ(res, 1);
EXPECT_EQ(settings.get_optional("param", 0), 1);
EXPECT_FALSE(settings.get<int>("param2", res));
EXPECT_EQ(settings.get_optional("param2", 0), 0);
EXPECT_TRUE(settings.get<int>("segment/param", res));
EXPECT_EQ(res, 2);
EXPECT_EQ(settings.get_optional("segment/param", 0), 2);
EXPECT_FALSE(settings.get<int>("segment/param2", res));
EXPECT_EQ(settings.get_optional("segment/param2", 0), 0);
EXPECT_FALSE(settings.get<int>("segment2/param", res));
EXPECT_EQ(settings.get_optional("segment2/param", 0), 0);
}
// Run all the tests that were declared with TEST()
int main(int argc, char **argv){
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

View File

@@ -0,0 +1,53 @@
// Bring in my package's API, which is what I'm testing
#include <socketcan_interface/string.h>
// Bring in gtest
#include <gtest/gtest.h>
TEST(StringTest, stringconversion)
{
const std::string s1("123#1234567812345678");
can::Frame f1 = can::toframe(s1);
EXPECT_EQ(s1, can::tostring(f1, true));
const std::string s2("1337#1234567812345678");
can::Frame f2 = can::toframe(s2);
EXPECT_FALSE(f2.isValid());
const std::string s3("80001337#1234567812345678");
const std::string s4("00001337#1234567812345678");
can::Frame f3 = can::toframe(s3);
EXPECT_EQ(f3.fullid(), 0x80001337);
EXPECT_TRUE(f3.isValid());
EXPECT_TRUE(f3.is_extended);
EXPECT_EQ(s4, can::tostring(f3, true)); // 8000 is converted to 0000
can::Frame f4 = can::toframe(s4);
EXPECT_EQ(f4.fullid(), 0x80001337);
EXPECT_TRUE(f4.isValid());
EXPECT_TRUE(f4.is_extended);
EXPECT_EQ(s4, can::tostring(f4, true));
const std::string s5("20001337#1234567812345678");
can::Frame f5 = can::toframe(s5);
EXPECT_EQ(f5.fullid(), 0xA0001337);
EXPECT_TRUE(f5.isValid());
EXPECT_TRUE(f5.is_error);
EXPECT_EQ(s5, can::tostring(f5, true));
const std::string s6("40001337#1234567812345678");
can::Frame f6 = can::toframe(s6);
EXPECT_EQ(f6.fullid(), 0xC0001337);
EXPECT_TRUE(f6.isValid());
EXPECT_TRUE(f6.is_rtr);
EXPECT_EQ(s6, can::tostring(f6, true));
}
// Run all the tests that were declared with TEST()
int main(int argc, char **argv){
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}