Skip to content

Commit

Permalink
feat(kmod): unit test for AGNOCAST_PUBLISH_MSG_CMD (#449)
Browse files Browse the repository at this point in the history
* Done

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* add some cases

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* apply cppcheck

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* make qos_depth global

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* fix

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* fix

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* fix

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* Update kmod/agnocast_kunit/agnocast_kunit_publish_msg.c

Co-authored-by: atsushi yano <55824710+atsushi421@users.noreply.github.com>

* fix

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* modify Makefile

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* add get_topic_entries_num

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

* Update agnocast_kmod/agnocast.c

Co-authored-by: Ryuta Kambe <ryuta.kambe@tier4.jp>

* fix for release_msgs_to_meet_depth

Signed-off-by: koichiimai <kotty.0704@gmail.com>

* fix comments

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>

---------

Signed-off-by: Koichi Imai <koichi.imai.2@tier4.jp>
Signed-off-by: koichiimai <kotty.0704@gmail.com>
Co-authored-by: atsushi yano <55824710+atsushi421@users.noreply.github.com>
Co-authored-by: Ryuta Kambe <ryuta.kambe@tier4.jp>
  • Loading branch information
3 people authored Mar 4, 2025
1 parent 7f488b7 commit b76a16d
Show file tree
Hide file tree
Showing 4 changed files with 308 additions and 11 deletions.
41 changes: 40 additions & 1 deletion agnocast_kmod/agnocast.c
Original file line number Diff line number Diff line change
Expand Up @@ -1015,7 +1015,6 @@ static int release_msgs_to_meet_depth(
"messages for this publisher to increase. (topic_name=%s, id=%d, entries_num=%d)."
"(release_msgs_to_meet_depth)\n",
wrapper->key, pub_info->id, pub_info->entries_num);
return -1;
}

struct rb_node * node = rb_first(&wrapper->topic.entries);
Expand Down Expand Up @@ -1602,6 +1601,46 @@ bool is_in_proc_info_htable(const pid_t pid)
return false;
}

int get_topic_entries_num(char * topic_name)
{
struct topic_wrapper * wrapper = find_topic(topic_name);
if (!wrapper) {
dev_warn(
agnocast_device, "Topic (topic_name=%s) not found. (get_topic_entries_num)\n", topic_name);
return -1;
}

struct rb_root * root = &wrapper->topic.entries;
struct rb_node ** new = &(root->rb_node);
int count = 0;
while (*new) {
new = &((*new)->rb_right);
count++;
}
return count;
}

bool is_in_topic_entries(char * topic_name, int64_t entry_id)
{
struct topic_wrapper * wrapper = find_topic(topic_name);
if (!wrapper) {
dev_warn(
agnocast_device, "Topic (topic_name=%s) not found. (is_in_topic_entries)\n", topic_name);
return false;
}
const struct entry_node * en = find_message_entry(wrapper, entry_id);
if (!en) {
dev_warn(
agnocast_device,
"Message entry (topic_name=%s entry_id=%lld) not found. "
"(is_in_topic_entries)\n",
topic_name, entry_id);
return false;
}

return true;
}

#endif

// =========================================
Expand Down
2 changes: 2 additions & 0 deletions agnocast_kmod/agnocast.h
Original file line number Diff line number Diff line change
Expand Up @@ -208,4 +208,6 @@ void process_exit_cleanup(const pid_t pid);
#ifdef KUNIT_BUILD
int get_proc_info_htable_size(void);
bool is_in_proc_info_htable(const pid_t pid);
int get_topic_entries_num(char * topic_name);
bool is_in_topic_entries(char * topic_name, int64_t entry_id);
#endif
256 changes: 250 additions & 6 deletions agnocast_kmod/agnocast_kunit/agnocast_kunit_publish_msg.c
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,258 @@

#include <kunit/test.h>

// Feel free to delete this test case
void test_case_publish_msg_sample0(struct kunit * test)
static char * topic_name = "/kunit_test_topic";
static char * node_name = "/kunit_test_node";
static uint32_t qos_depth = 1;
static bool qos_is_transient_local = false;
static pid_t subscriber_pid = 1000;
static pid_t publisher_pid = 2000;
static bool is_take_sub = false;

static void setup_one_subscriber(struct kunit * test, topic_local_id_t * subscriber_id)
{
subscriber_pid++;

union ioctl_new_shm_args new_shm_args;
int ret1 = new_shm_addr(subscriber_pid, PAGE_SIZE, &new_shm_args);

union ioctl_subscriber_args subscriber_args;
int ret2 = subscriber_add(
topic_name, node_name, subscriber_pid, qos_depth, qos_is_transient_local, is_take_sub,
&subscriber_args);
*subscriber_id = subscriber_args.ret_id;

KUNIT_ASSERT_EQ(test, ret1, 0);
KUNIT_ASSERT_EQ(test, ret2, 0);
}

static void setup_one_publisher(
struct kunit * test, topic_local_id_t * publisher_id, uint64_t * ret_addr)
{
publisher_pid++;

union ioctl_new_shm_args new_shm_args;
int ret1 = new_shm_addr(publisher_pid, PAGE_SIZE, &new_shm_args);
*ret_addr = new_shm_args.ret_addr;

union ioctl_publisher_args publisher_args;
int ret2 = publisher_add(
topic_name, node_name, publisher_pid, qos_depth, qos_is_transient_local, &publisher_args);
*publisher_id = publisher_args.ret_id;

KUNIT_ASSERT_EQ(test, ret1, 0);
KUNIT_ASSERT_EQ(test, ret2, 0);
}

// Expect to fail at find_topic()
void test_case_no_topic(struct kunit * test)
{
// Arrange
topic_local_id_t publisher_id = 0;
uint64_t msg_virtual_address = 0x40000000000;
union ioctl_publish_args ioctl_publish_ret;

// Act
int ret = publish_msg(topic_name, publisher_id, msg_virtual_address, &ioctl_publish_ret);

// Assert
KUNIT_EXPECT_EQ(test, ret, -1);
}

// Expect to fail at find_publisher_info
void test_case_no_publisher(struct kunit * test)
{
KUNIT_EXPECT_EQ(test, 1 + 1, 2);
// Arrange
topic_local_id_t subscriber_id;
setup_one_subscriber(test, &subscriber_id);

topic_local_id_t publisher_id = 0;
uint64_t msg_virtual_address = 0x40000000000;
union ioctl_publish_args ioctl_publish_msg_ret;

// Act
int ret = publish_msg(topic_name, publisher_id, msg_virtual_address, &ioctl_publish_msg_ret);

// Assert
KUNIT_ASSERT_EQ(test, ret, -1);
}

void test_case_simple_publish_without_any_release(struct kunit * test)
{
// Arrange
topic_local_id_t publisher_id;
uint64_t ret_addr;
setup_one_publisher(test, &publisher_id, &ret_addr);

union ioctl_publish_args ioctl_publish_msg_ret;

// Act
int ret = publish_msg(topic_name, publisher_id, ret_addr, &ioctl_publish_msg_ret);

// Assert
KUNIT_EXPECT_EQ(test, ret, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_released_num, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_subscriber_num, 0);
KUNIT_EXPECT_EQ(test, is_in_topic_entries(topic_name, ioctl_publish_msg_ret.ret_entry_id), true);
KUNIT_EXPECT_EQ(test, get_topic_entries_num(topic_name), 1);
}

void test_case_different_publisher_no_release(struct kunit * test)
{
// Arrange
topic_local_id_t publisher_id1, publisher_id2;
uint64_t ret_addr1, ret_addr2;
setup_one_publisher(test, &publisher_id1, &ret_addr1);
setup_one_publisher(test, &publisher_id2, &ret_addr2);

union ioctl_publish_args ioctl_publish_msg_ret1;
int ret1 = publish_msg(topic_name, publisher_id1, ret_addr1, &ioctl_publish_msg_ret1);
int ret2 =
decrement_message_entry_rc(topic_name, publisher_id1, ioctl_publish_msg_ret1.ret_entry_id);
KUNIT_ASSERT_EQ(test, ret1, 0);
KUNIT_ASSERT_EQ(test, ret2, 0);

union ioctl_publish_args ioctl_publish_msg_ret2;

// Act
int ret3 = publish_msg(topic_name, publisher_id2, ret_addr2, &ioctl_publish_msg_ret2);

// Assert
KUNIT_EXPECT_EQ(test, ret3, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret2.ret_released_num, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret2.ret_subscriber_num, 0);
KUNIT_EXPECT_EQ(test, is_in_topic_entries(topic_name, ioctl_publish_msg_ret1.ret_entry_id), true);
KUNIT_EXPECT_EQ(test, is_in_topic_entries(topic_name, ioctl_publish_msg_ret2.ret_entry_id), true);
KUNIT_EXPECT_EQ(test, get_topic_entries_num(topic_name), 2);
}

// Feel free to delete this test case
void test_case_publish_msg_sample1(struct kunit * test)
void test_case_referenced_node_not_released(struct kunit * test)
{
KUNIT_EXPECT_EQ(test, 1 * 1, 1);
// Arrange
topic_local_id_t publisher_id;
uint64_t ret_addr;
setup_one_publisher(test, &publisher_id, &ret_addr);

union ioctl_publish_args ioctl_publish_msg_ret1;
int ret1 = publish_msg(topic_name, publisher_id, ret_addr, &ioctl_publish_msg_ret1);
KUNIT_ASSERT_EQ(test, ret1, 0);

union ioctl_publish_args ioctl_publish_msg_ret2;

// Act
int ret2 = publish_msg(topic_name, publisher_id, ret_addr + 1, &ioctl_publish_msg_ret2);

// Assert
KUNIT_EXPECT_EQ(test, ret2, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret2.ret_released_num, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret2.ret_subscriber_num, 0);
KUNIT_EXPECT_EQ(test, is_in_topic_entries(topic_name, ioctl_publish_msg_ret1.ret_entry_id), true);
KUNIT_EXPECT_EQ(test, is_in_topic_entries(topic_name, ioctl_publish_msg_ret2.ret_entry_id), true);
KUNIT_EXPECT_EQ(test, get_topic_entries_num(topic_name), 2);
}

void test_case_single_release_return(struct kunit * test)
{
// Arrange
topic_local_id_t publisher_id;
uint64_t ret_addr;
setup_one_publisher(test, &publisher_id, &ret_addr);

union ioctl_publish_args ioctl_publish_msg_ret1;
int ret1 = publish_msg(topic_name, publisher_id, ret_addr, &ioctl_publish_msg_ret1);
int ret2 =
decrement_message_entry_rc(topic_name, publisher_id, ioctl_publish_msg_ret1.ret_entry_id);
KUNIT_ASSERT_EQ(test, ret1, 0);
KUNIT_ASSERT_EQ(test, ret2, 0);

union ioctl_publish_args ioctl_publish_msg_ret2;

// Act
int ret3 = publish_msg(topic_name, publisher_id, ret_addr + 1, &ioctl_publish_msg_ret2);

// Assert
KUNIT_EXPECT_EQ(test, ret3, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret2.ret_released_num, 1);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret2.ret_released_addrs[0], ret_addr);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret2.ret_subscriber_num, 0);
KUNIT_EXPECT_EQ(
test, is_in_topic_entries(topic_name, ioctl_publish_msg_ret1.ret_entry_id), false);
KUNIT_EXPECT_EQ(test, is_in_topic_entries(topic_name, ioctl_publish_msg_ret2.ret_entry_id), true);
KUNIT_EXPECT_EQ(test, get_topic_entries_num(topic_name), 1);
}

void test_case_excessive_release_count(struct kunit * test)
{
// Arrange
topic_local_id_t publisher_id;
uint64_t ret_addr;
setup_one_publisher(test, &publisher_id, &ret_addr);

int64_t entry_ids[MAX_RELEASE_NUM + 1];
for (int i = 0; i < MAX_RELEASE_NUM + 1; i++) {
union ioctl_publish_args ioctl_publish_msg_ret;
int ret = publish_msg(topic_name, publisher_id, ret_addr + i, &ioctl_publish_msg_ret);
entry_ids[i] = ioctl_publish_msg_ret.ret_entry_id;

KUNIT_ASSERT_EQ(test, ret, 0);
}

for (int i = 0; i < MAX_RELEASE_NUM + 1; i++) {
int ret = decrement_message_entry_rc(topic_name, publisher_id, entry_ids[i]);
KUNIT_ASSERT_EQ(test, ret, 0);
}

union ioctl_publish_args ioctl_publish_msg_ret;

// Act
int ret = publish_msg(topic_name, publisher_id, ret_addr, &ioctl_publish_msg_ret);

// Assert
KUNIT_EXPECT_EQ(test, ret, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_released_num, MAX_RELEASE_NUM);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_subscriber_num, 0);
KUNIT_EXPECT_EQ(test, get_topic_entries_num(topic_name), 2);
}

void test_case_ret_one_subscriber(struct kunit * test)
{
// Arrange
topic_local_id_t publisher_id, subscriber_id;
uint64_t ret_addr;
setup_one_publisher(test, &publisher_id, &ret_addr);
setup_one_subscriber(test, &subscriber_id);

union ioctl_publish_args ioctl_publish_msg_ret;

// Act
int ret = publish_msg(topic_name, publisher_id, ret_addr, &ioctl_publish_msg_ret);

// Assert
KUNIT_EXPECT_EQ(test, ret, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_released_num, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_subscriber_num, 1);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_subscriber_ids[0], subscriber_id);
}

void test_case_ret_many_subscribers(struct kunit * test)
{
// Arrange
topic_local_id_t publisher_id;
uint64_t ret_addr;
setup_one_publisher(test, &publisher_id, &ret_addr);

for (int i = 0; i < MAX_SUBSCRIBER_NUM; i++) {
topic_local_id_t subscriber_id;
setup_one_subscriber(test, &subscriber_id);
}

union ioctl_publish_args ioctl_publish_msg_ret;

// Act
int ret = publish_msg(topic_name, publisher_id, ret_addr, &ioctl_publish_msg_ret);

// Assert
KUNIT_EXPECT_EQ(test, ret, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_released_num, 0);
KUNIT_EXPECT_EQ(test, ioctl_publish_msg_ret.ret_subscriber_num, MAX_SUBSCRIBER_NUM);
}
20 changes: 16 additions & 4 deletions agnocast_kmod/agnocast_kunit/agnocast_kunit_publish_msg.h
Original file line number Diff line number Diff line change
@@ -1,8 +1,20 @@
#pragma once
#include <kunit/test.h>

#define TEST_CASES_PUBLISH_MSG \
KUNIT_CASE(test_case_publish_msg_sample0), KUNIT_CASE(test_case_publish_msg_sample1)
#define TEST_CASES_PUBLISH_MSG \
KUNIT_CASE(test_case_no_topic), KUNIT_CASE(test_case_no_publisher), \
KUNIT_CASE(test_case_simple_publish_without_any_release), \
KUNIT_CASE(test_case_different_publisher_no_release), \
KUNIT_CASE(test_case_referenced_node_not_released), \
KUNIT_CASE(test_case_single_release_return), KUNIT_CASE(test_case_excessive_release_count), \
KUNIT_CASE(test_case_ret_one_subscriber), KUNIT_CASE(test_case_ret_many_subscribers)

void test_case_publish_msg_sample0(struct kunit * test);
void test_case_publish_msg_sample1(struct kunit * test);
void test_case_no_topic(struct kunit * test);
void test_case_no_publisher(struct kunit * test);
void test_case_simple_publish_without_any_release(struct kunit * test);
void test_case_different_publisher_no_release(struct kunit * test);
void test_case_referenced_node_not_released(struct kunit * test);
void test_case_single_release_return(struct kunit * test);
void test_case_excessive_release_count(struct kunit * test);
void test_case_ret_one_subscriber(struct kunit * test);
void test_case_ret_many_subscribers(struct kunit * test);

0 comments on commit b76a16d

Please sign in to comment.