多旋翼无人机

    返回首页    发表留言
本文作者:李德强
          第三节 创建并运行线程
 
 

        在本节中我们来主要学习创建并运行多线程的相关知识。我们知道进程与线程都是操作系统为可执行程序所提供一种可以并发执行的调度机制,它允许一个进程内可以创建多个并行执行的线程,这些线程可以与进程一样享有其代码段和数据段内容,只不过每一个线程都有独立的函数栈。我们来看一下创建线程的函数:

/****************************************************************************
 * Name:  pthread_create
 *
 * Description:
 *   This function creates and activates a new thread with a specified
 *   attributes.
 *
 * Input Parameters:
 *    thread
 *    attr
 *    start_routine
 *    arg
 *
 * Returned value:
 *   OK (0) on success; a (non-negated) errno value on failure. The errno
 *   variable is not set.
 *
 ****************************************************************************/

int pthread_create(FAR pthread_t *thread, FAR const pthread_attr_t *attr,
                   pthread_startroutine_t start_routine, pthread_addr_t arg)

        这个pthread_create()函数是一个遵守posix标准的创建线程函数,我们来对它的几个参数做一下简要说明:

        pthread_t *thread:线程标识符,用于对需要创建并运行的线程进行标识,也可以说是此线程的唯一描述符。

        pthread_attr_t *attr:线程属性,其中定义了线程所使用栈内存的大小,调度优先级等等。

        pthread_startroutine_t start_routine:线程运行函数入口,这是一个函数指针,用于指向一个等待运行的函数。

        pthread_addr_t arg:运行参数,此线程在调用需要运行的函数start_routine时为其传入的参数。

        另外,还有几个函数需要简单介绍一下:

 

//初始化线程属性
int pthread_attr_init(FAR pthread_attr_t *attr)
//销毁线程属性
int pthread_attr_destroy(FAR pthread_attr_t *attr)
//设置线程栈内存大小
int pthread_attr_setstacksize(FAR pthread_attr_t *attr, 
                              long stacksize)
//取得线程调度参数
int pthread_attr_getschedparam(FAR const pthread_attr_t *attr, 
                               FAR struct sched_param *param)
//设置线程调度参数
int pthread_attr_setschedparam(FAR pthread_attr_t *attr, 
                               FAR const struct sched_param *param)

       接下来我们就可以在上一节的例子的基础上继续编写程序,创建一个全局变量int _run用于标识线程和进程的循环条件,并在process_test进程中创建两个不同的线程:

#include <stdio.h>
#include <unistd.h>
#include <string.h>
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_tasks.h>

static int _run = 0;

int process_test_main(int argc, char *argv[]);
int process_test_task(int argc, char *argv[]);
void* pth_run(void *arg);

int process_test_task(int argc, char *argv[])
{
	//初始化线程属性并设定栈内存1000字节
	pthread_attr_t pth_attr;
	pthread_attr_init(&pth_attr);
	pthread_attr_setstacksize(&pth_attr, 1000);
	//设置线程优先级为100
	struct sched_param pth_param;
	pthread_attr_getschedparam(&pth_attr, &pth_param);
	pth_param.sched_priority = 100;
	pthread_attr_setschedparam(&pth_attr, &pth_param);
	//创建并运行两个线程,参数分别为1和2
	pthread_t pth;
	pthread_create(&pth, &pth_attr, pth_run, (void *) 1);
	pthread_create(&pth, &pth_attr, pth_run, (void *) 2);
	pthread_attr_destroy(&pth_attr);

	while (_run)
	{
		printf("Process: running.\n");
		sleep(1);
	}
	return 0;
}

void* pth_run(void *arg)
{
	//设置线程名称
	char pth_name[20];
	snprintf(pth_name, 20, "pth_%d", getpid());
	prctl(PR_SET_NAME, pth_name, getpid());

	while (_run)
	{
		printf("Pthread: arg is %d\n", (int) arg);
		sleep(1);
	}
	return NULL;
}

int process_test_main(int argc, char *argv[])
{
	if (argc < 2)
	{
		return -1;
	}
	if (!strcmp(argv[1], "start"))
	{
		if (_run)
		{
			return -1;
		}
		_run = 1;
		px4_task_spawn_cmd("process_test", SCHED_DEFAULT, 100, 2048, 
				(px4_main_t) process_test_task, (char * const *) argv);
		return 0;
	}
	if (!strcmp(argv[1], "stop"))
	{
		_run = 0;
	}
	return 0;
}

        编写好源代码之后,我们在nsh中执行process_test start即可以看到process_test进程和两个线程并行运行:

        同时我们可以执行top命令来查看它们的运行情况:

 

 

 

    返回首页    返回顶部
  看不清?点击刷新

 

  Copyright © 2015-2023 问渠网 辽ICP备15013245号