【RK3399Pro学习笔记】十九、在ROS中点亮LED灯

目录

  • 创建ROS工作空间
  • 创建ROS功能包
    • C++
      • SysFs方式(需root)
        • 源文件
          • blink.cpp
          • gpiolib.cpp
        • 头文件
          • gpiolib.h
        • CMakeLists.txt
        • 运行代码
      • 调用shell命令方式(无需root)
        • 源文件
          • blink.cpp
        • CMakeLists.txt
        • 运行代码

平台:华硕 Thinker Edge R 瑞芯微 RK3399Pro
固件版本:Tinker_Edge_R-Debian-Stretch-V1.0.4-20200615


创建ROS工作空间

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
catkin_init_workspace

回到工作目录根空间使用catkin_make命令编译整个空间:

cd ~/catkin_ws/
catkin_make

创建ROS功能包

进入工作空间,使用catkin_create_pkg命令创建功能包:

cd ~/catkin_ws/src
catkin_create_pkg ROS_Test_LED std_msgs rospy roscpp

C++

(参考ROS 树莓派小车制作(一) ——ROS “点灯” —— 支链)
为了更具普适性,这里使用自定义的源码(来自SysFs方式下C语言控制GPIO(RK3399)—— 姚家湾)来点灯,其它方式见【RK3399Pro学习笔记】十八、点亮LED灯(python、C语言、bash)

SysFs方式(需root)

源文件

cd ~/catkin_ws/src/ROS_Test_LED/src
blink.cpp
nano blink.cpp
#include "ros/ros.h"
#include "std_msgs/Bool.h"#include <iostream>
#include "ROS_Test_LED/gpiolib.h"void blink_callback(const std_msgs::Bool::ConstPtr& msg)
{gpio_export(73);if(msg->data==1){gpio_write(73, 0);ROS_INFO("LED ON");}if(msg->data==0){gpio_write(73, 1);ROS_INFO("LED OFF");}gpio_unexport(73);
}int main(int argc,char** argv)
{ros::init(argc,argv,"blink_led");ROS_INFO("Started Blink Node");ros::NodeHandle n;ros::Subscriber sub=n.subscribe("led_blink",10,blink_callback);ros::spin();
}
gpiolib.cpp
nano gpiolib.cpp
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <fcntl.h>
#include <unistd.h>
#include <sys/select.h>
#include <sys/stat.h>
#include "ROS_Test_LED/gpiolib.h"int gpio_direction(int gpio, int dir)
{int ret = 0;char buf[50];sprintf(buf, "/sys/class/gpio/gpio%d/direction", gpio);int gpiofd = open(buf, O_WRONLY);if (gpiofd < 0){perror("Couldn't open IRQ file");ret = -1;}if (dir == 2 && gpiofd){if (3 != write(gpiofd, "high", 3)){perror("Couldn't set GPIO direction to out");ret = -2;}}if (dir == 1 && gpiofd){if (3 != write(gpiofd, "out", 3)){perror("Couldn't set GPIO direction to out");ret = -3;}}else if (gpiofd){if (2 != write(gpiofd, "in", 2)){perror("Couldn't set GPIO directio to in");ret = -4;}}close(gpiofd);return ret;
}int gpio_setedge(int gpio, int rising, int falling)
{int ret = 0;char buf[50];sprintf(buf, "/sys/class/gpio/gpio%d/edge", gpio);int gpiofd = open(buf, O_WRONLY);if (gpiofd < 0){perror("Couldn't open IRQ file");ret = -1;}if (gpiofd && rising && falling){if (4 != write(gpiofd, "both", 4)){perror("Failed to set IRQ to both falling & rising");ret = -2;}}else{if (rising && gpiofd){if (6 != write(gpiofd, "rising", 6)){perror("Failed to set IRQ to rising");ret = -2;}}else if (falling && gpiofd){if (7 != write(gpiofd, "falling", 7)){perror("Failed to set IRQ to falling");ret = -3;}}}close(gpiofd);return ret;
}int gpio_export(int gpio)
{int efd;char buf[50];int gpiofd, ret;/* Quick test if it has already been exported */sprintf(buf, "/sys/class/gpio/gpio%d/value", gpio);efd = open(buf, O_WRONLY);if (efd != -1){close(efd);return 0;}efd = open("/sys/class/gpio/export", O_WRONLY);if (efd != -1){sprintf(buf, "%d", gpio);ret = write(efd, buf, strlen(buf));if (ret < 0){perror("Export failed");return -2;}close(efd);}else{// If we can't open the export file, we probably// dont have any gpio permissionsreturn -1;}return 0;
}void gpio_unexport(int gpio)
{int gpiofd, ret;char buf[50];gpiofd = open("/sys/class/gpio/unexport", O_WRONLY);sprintf(buf, "%d", gpio);ret = write(gpiofd, buf, strlen(buf));close(gpiofd);
}int gpio_getfd(int gpio)
{char in[3] = {0, 0, 0};char buf[50];int gpiofd;sprintf(buf, "/sys/class/gpio/gpio%d/value", gpio);gpiofd = open(buf, O_RDWR);if (gpiofd < 0){fprintf(stderr, "Failed to open gpio %d value\n", gpio);perror("gpio failed");}return gpiofd;
}int gpio_read(int gpio)
{char in[3] = {0, 0, 0};char buf[50];int nread, gpiofd;sprintf(buf, "/sys/class/gpio/gpio%d/value", gpio);gpiofd = open(buf, O_RDWR);if (gpiofd < 0){fprintf(stderr, "Failed to open gpio %d value\n", gpio);perror("gpio failed");}do{nread = read(gpiofd, in, 1);} while (nread == 0);if (nread == -1){perror("GPIO Read failed");return -1;}close(gpiofd);return atoi(in);
}int gpio_write(int gpio, int val)
{char buf[50];int nread, ret, gpiofd;sprintf(buf, "/sys/class/gpio/gpio%d/value", gpio);gpiofd = open(buf, O_RDWR);if (gpiofd > 0){snprintf(buf, 2, "%d", val);ret = write(gpiofd, buf, 2);if (ret < 0){perror("failed to set gpio");return 1;}close(gpiofd);if (ret == 2)return 0;}return 1;
}int gpio_select(int gpio)
{char gpio_irq[64];int ret = 0, buf, irqfd;fd_set fds;FD_ZERO(&fds);snprintf(gpio_irq, sizeof(gpio_irq), "/sys/class/gpio/gpio%d/value", gpio);irqfd = open(gpio_irq, O_RDONLY, S_IREAD);if (irqfd < 1){perror("Couldn't open the value file");return -13;}// Read first since there is always an initial statusret = read(irqfd, &buf, sizeof(buf));while (1){FD_SET(irqfd, &fds);ret = select(irqfd + 1, NULL, NULL, &fds, NULL);if (FD_ISSET(irqfd, &fds)){FD_CLR(irqfd, &fds); // Remove the filedes from set// Clear the junk data in the IRQ fileret = read(irqfd, &buf, sizeof(buf));return 1;}}
}

头文件

cd ~/catkin_ws/src/ROS_Test_LED/include/ROS_Test_LED
gpiolib.h
nano gpiolib.h
#ifndef _GPIOLIB_H_
#define _GPIOLIB_H_/* returns -1 or the file descriptor of the gpio value file */
int gpio_export(int gpio);
/* Set direction to 2 = high output, 1 low output, 0 input */
int gpio_direction(int gpio, int dir);
/* Release the GPIO to be claimed by other processes or a kernel driver */
void gpio_unexport(int gpio);
/* Single GPIO read */
int gpio_read(int gpio);
/* Set GPIO to val (1 = high) */
int gpio_write(int gpio, int val);
/* Set which edge(s) causes the value select to return */
int gpio_setedge(int gpio, int rising, int falling);
/* Blocks on select until GPIO toggles on edge */
int gpio_select(int gpio);/* Return the GPIO file descriptor */
int gpio_getfd(int gpio);#endif //_GPIOLIB_H_

CMakeLists.txt

nano ~/catkin_ws/src/ROS_Test_LED/CMakeLists.txt
cmake_minimum_required(VERSION 3.0.2)
project(ROS_Test_LED)## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTSroscpprospystd_msgs
)## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()################################################
## Declare ROS messages, services and actions ##
################################################## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
##   * add a build_depend tag for "message_generation"
##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in
##     but can be declared for certainty nonetheless:
##     * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
##   * add "message_generation" and every package in MSG_DEP_SET to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * add "message_runtime" and every package in MSG_DEP_SET to
##     catkin_package(CATKIN_DEPENDS ...)
##   * uncomment the add_*_files sections below as needed
##     and list every .msg/.srv/.action file to be processed
##   * uncomment the generate_messages entry below
##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)## Generate messages in the 'msg' folder
# add_message_files(
#   FILES
#   Message1.msg
#   Message2.msg
# )## Generate services in the 'srv' folder
# add_service_files(
#   FILES
#   Service1.srv
#   Service2.srv
# )## Generate actions in the 'action' folder
# add_action_files(
#   FILES
#   Action1.action
#   Action2.action
# )## Generate added messages and services with any dependencies listed here
# generate_messages(
#   DEPENDENCIES
#   std_msgs
# )################################################
## Declare ROS dynamic reconfigure parameters ##
################################################## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
##   * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
##   * add "dynamic_reconfigure" to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * uncomment the "generate_dynamic_reconfigure_options" section below
##     and list every .cfg file to be processed## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
#   cfg/DynReconf1.cfg
#   cfg/DynReconf2.cfg
# )###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES ROS_Test_LED
#  CATKIN_DEPENDS roscpp rospy std_msgs
#  DEPENDS system_lib
)###########
## Build ##
############# Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(include${catkin_INCLUDE_DIRS}
)## Declare a C++ library
# add_library(${PROJECT_NAME}
#   src/${PROJECT_NAME}/ROS_Test_LED.cpp
# )## 用来手动链接头文件和源文件
add_library(gpiolib                 ## 自定义的链接库名,后面用来识别include/ROS_Test_LED/gpiolib.h  ## 头文件的路径src/gpiolib.cpp                 ## 源文件的路径
)
add_dependencies(gpiolib ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(gpiolib ${catkin_LIBRARIES}
)## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/ROS_Test_LED_node.cpp)add_executable(blink_led src/blink.cpp)## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
#   ${catkin_LIBRARIES}
# )add_dependencies(blink_led ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(blink_led gpiolib${catkin_LIBRARIES}
)#############
## Install ##
############## all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
#   scripts/my_python_script
#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
#   FILES_MATCHING PATTERN "*.h"
#   PATTERN ".svn" EXCLUDE
# )## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
#   # myfile1
#   # myfile2
#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )#############
## Testing ##
############### Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_ROS_Test_LED.cpp)
# if(TARGET ${PROJECT_NAME}-test)
#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

回到工作空间根目录进行编译

cd ~/catkin_ws
catkin_make

运行代码

由于控制GPIO需要root权限,故ros相关命令也要以root身份执行:
新建一个终端

sudo -s
source ./catkin_ws/devel/setup.bash
roscore

新建一个终端

sudo -s
source ./catkin_ws/devel/setup.bash
rosrun ROS_Test_LED blink_led

新建一个终端

sudo -s
source ./catkin_ws/devel/setup.bash

改变电平:

rostopic pub /led_blink std_msgs/Bool 1

在这里插入图片描述

rostopic pub /led_blink std_msgs/Bool 0

在这里插入图片描述

新建一个终端

rqt_graph

在这里插入图片描述

调用shell命令方式(无需root)

源文件

cd ~/catkin_ws/src/ROS_Test_LED/src
blink.cpp
nano blink.cpp
#include "ros/ros.h"
#include "std_msgs/Bool.h"#include <iostream>
#include <stdlib.h>void blink_callback(const std_msgs::Bool::ConstPtr& msg)
{if(msg->data==1){system("gpio write 8 0");ROS_INFO("LED ON");}if(msg->data==0){system("gpio write 8 1");ROS_INFO("LED OFF");}
}int main(int argc,char** argv)
{ros::init(argc,argv,"blink_led");ROS_INFO("Started Blink Node");system("gpio mode 8 out");system("gpio write 8 1");ros::NodeHandle n;ros::Subscriber sub=n.subscribe("led_blink",10,blink_callback);ros::spin();
}

其中8为wiringPi的引脚编号,可通过gpio readall命令查看
在这里插入图片描述

CMakeLists.txt

nano ~/catkin_ws/src/ROS_Test_LED/CMakeLists.txt
cmake_minimum_required(VERSION 3.0.2)
project(ROS_Test_LED)## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTSroscpprospystd_msgs
)## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()################################################
## Declare ROS messages, services and actions ##
################################################## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
##   * add a build_depend tag for "message_generation"
##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in
##     but can be declared for certainty nonetheless:
##     * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
##   * add "message_generation" and every package in MSG_DEP_SET to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * add "message_runtime" and every package in MSG_DEP_SET to
##     catkin_package(CATKIN_DEPENDS ...)
##   * uncomment the add_*_files sections below as needed
##     and list every .msg/.srv/.action file to be processed
##   * uncomment the generate_messages entry below
##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)## Generate messages in the 'msg' folder
# add_message_files(
#   FILES
#   Message1.msg
#   Message2.msg
# )## Generate services in the 'srv' folder
# add_service_files(
#   FILES
#   Service1.srv
#   Service2.srv
# )## Generate actions in the 'action' folder
# add_action_files(
#   FILES
#   Action1.action
#   Action2.action
# )## Generate added messages and services with any dependencies listed here
# generate_messages(
#   DEPENDENCIES
#   std_msgs
# )################################################
## Declare ROS dynamic reconfigure parameters ##
################################################## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
##   * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
##   * add "dynamic_reconfigure" to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * uncomment the "generate_dynamic_reconfigure_options" section below
##     and list every .cfg file to be processed## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
#   cfg/DynReconf1.cfg
#   cfg/DynReconf2.cfg
# )###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES ROS_Test_LED
#  CATKIN_DEPENDS roscpp rospy std_msgs
#  DEPENDS system_lib
)###########
## Build ##
############# Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(include${catkin_INCLUDE_DIRS}
)## Declare a C++ library
# add_library(${PROJECT_NAME}
#   src/${PROJECT_NAME}/ROS_Test_LED.cpp
# )## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/ROS_Test_LED_node.cpp)add_executable(blink_led src/blink.cpp)## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
#   ${catkin_LIBRARIES}
# )add_dependencies(blink_led ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(blink_led ${catkin_LIBRARIES}
)#############
## Install ##
############## all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
#   scripts/my_python_script
#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
#   FILES_MATCHING PATTERN "*.h"
#   PATTERN ".svn" EXCLUDE
# )## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
#   # myfile1
#   # myfile2
#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )#############
## Testing ##
############### Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_ROS_Test_LED.cpp)
# if(TARGET ${PROJECT_NAME}-test)
#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

回到工作空间根目录进行编译

cd ~/catkin_ws
catkin_make

运行代码

新建一个终端

source ~/catkin_ws/devel/setup.bash
roscore

新建一个终端

source ~/catkin_ws/devel/setup.bash
rosrun ROS_Test_LED blink_led

新建一个终端

source ~/catkin_ws/devel/setup.bash

改变电平:

rostopic pub /led_blink std_msgs/Bool 1
rostopic pub /led_blink std_msgs/Bool 0

新建一个终端

rqt_graph

在这里插入图片描述

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.mzph.cn/news/400010.shtml

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

opencv中的Mat类型

Mat类型主要是跟matlab中的数据类型一样。故用起来很方便。 Mat最大的优势跟STL很相似&#xff0c;都是对内存进行动态的管理&#xff0c;不需要之前用户手动的管理内存&#xff0c;对于一些大型的开发&#xff0c;有时候投入的lpImage内存管理的时间甚至比关注算法实现的时间还…

C/C++与内存相关的函数

C语言的标准函数库与内存管理有关的函数从功能上分为两类:一类是系统对内存操作的函数,例如,读内存的函数、写内存函数,如从指定地址向内存写一个字节,一个字或向内存读一个字节或一个字操作;另一类是供用户动态使用内存的函数,例如,分配C程序一块存储区,并将该区清零函数; 1.动…

flask jinja2 如何遍历新闻列表

NEWS_DICT [{"newstitle": "新闻1", "url": "newsurl1"},{"newstitle": "新闻2", "url": "newsurl2"},{"newstitle": "新闻3", "url": "newsurl3"…

hihocoder [Offer收割]编程练习赛24

比赛https://hihocoder.com/contest/offers24/problems 应该能拿到个鼠标垫 舒服了 这个oj体验好差&#xff0c;每次都要先因为选错语言CE一发&#xff0c;而且刷新之后还是默认GCC A ⼩Hi的钟表 算秒数&#xff0c;算角度&#xff0c;注意180以内&#xff0c;所以大于180之后拿…

LaTex bib引用知网论文NoteExpress格式文献 —— cnki2bib

目录先决条件安装使用最后…棘手的用法简单用法获取NoteExpress格式到剪贴板将剪贴板内容转换在LaTex中使用调用格式效果TeXstudio 4.2.3 Windows 10 20H2 以下内容引自Python cnki2bib包介绍 先决条件 Python3 安装 pip install cnki2bibWinR打开cmd使用以上命令安装 使…

测试配置yum仓库的http镜像

测试配置yum仓库的http镜像一、基础环境 1、在tvm-base的基础上&#xff0c;复制一个镜像为tvm-yum来测试。 2、网络&#xff1a; eth0&#xff1a;host-only&#xff08;用于虚拟内网&#xff0c;手动固定IP&#xff0c;这样从宿主机可以直接连接到这个vm&#xff09; eth1&am…

24. 设计原则

总的来说是高内聚低耦合&#xff0c;内聚是把变化点进行封装&#xff0c;耦合还是要有的&#xff0c;只是要尽量少&#xff0c;不同内聚点的联系方式有两种&#xff0c;一种就是继承&#xff0c;一种就是组合。组合又分为基于接口组合还是基于类组合&#xff0c;基于接口就可以…

js中 json详解

var aa {name:"zoumm",age:23};var bb JSON.stringify(aa);console.log(bb); //打印出{"name":"zoumm","age":23} json的语法可以表示以下三种类型的值。 1、简单值&#xff1a;可以在json中表示字符串、数值、布尔和null。 2、对…

纸张大小

A0到A10的纸张尺寸表 纸的型号高(mm)x宽&#xff08;mm&#xff09;毫米高(mm)x宽(mm)英寸4A02378 x 1682 mm93.6 x 66.2 in2A01682 x 1189 mm66.2 x 46.8 inA01189 x 841 mm46.8 x 33.1 inA1841 x 594 mm33.1 x 23.4 inA2594 x 420 mm23.4 x 16.5 inA3420 x 297 mm16.5 x 11.7…

试用合肥工业大学学位论文 LaTeX 模板(HFUT_Thesis)

目录编辑器模板下载TeXstudio 4.2.3 Windows 10 20H2 编辑器 编辑器的下载和安装参考Latex下载 —— 倔强菜鸟(转载) 模板下载 见合肥工业大学硕士毕业论文的LaTex模板? 感谢大佬~ 大佬的项目地址&#xff1a;https://github.com/HFUTTUG/HFUT_Thesis/releases 下载下来后…

[CareerCup] 1.1 Unique Characters of a String 字符串中不同的字符

1.1 Implement an algorithm to determine if a string has all unique characters. What if you cannot use additional data structure? 这道题让我们判断一个字符串中是否有重复的字符&#xff0c;要求不用特殊的数据结构&#xff0c;这里应该是指哈希表之类的不让用。像普…

怎么查询局域网内全部电脑IP和mac地址..

在局域网内查询在线主机的IP一般比较简单&#xff0c;但局域网内全部电脑的IP怎么才能够查到呢&#xff1f;查询到IP后我还要知道对方的一些详细信息&#xff08;如MAC地址、电脑名称等&#xff09;该怎么查询呢&#xff1f;&#xff1f;&#xff1f; 工具/原料 Windows 网络 方…

python flask 通过ajax向后台传递数组参数

https://blog.csdn.net/m0_38061194/article/details/78851152 ajax 像后台传递参数&#xff0c;一般是字典的形式传递&#xff0c;但是如果字典的value的值是一个数组的话&#xff0c;通过request.form 获取得到的结果是 None。这是就需要把数组对象转化为json字符串&#xf…

JS,JQuery杂谈

JS返回页面&#xff1a; JS返回前一个页面&#xff0c;经常看到有人用window.history.go(-1)这种方法 这种放的确可以返回&#xff0c;也仅仅只是返回&#xff0c;返回的页面信息却没有刷新。也有人用windows.history.back()&#xff0c;但是经常返回的时候会丢失页面&#xf…

C语言一阶低通、高通滤波器滤除截止频率外的杂波

目录理论推导产生测试信号sin_cal.csin_cal.h生成波形一阶滤波器FirstOrderFilter.cFirstOrderFilter.h测试低通滤波器高通滤波器IAP15W4K58S4 Keil uVision V5.29.0.0 PK51 Prof.Developers Kit Version:9.60.0.0 串口示波器&#xff1a;Vofa 1.3.10 理论推导 低通滤波器 …

OAF_开发系列19_实现OAF对话框提示dialogPage(案例)

20150716 Created By BaoXinjian 一、摘要 Oracle dialogPage是OAF提示框的一种用法&#xff0c;具体应用例如在删除数据时&#xff0c;提示用户进行确认是否可以删除 二、实现方法 在CO中添加如下方法 public void processFormRequest(OAPageContext pageContext,OAWebBean we…

flask ajax 笔记

html 其中 {{url_for(add)}} 的 add 为 flask 路由函数名 dataType: "json", 加了这句&#xff0c;才能读到 flask 返回的 json var my_tra_info {"key1":"val1","key2":val2};$.ajax({type:post,async:false,url:"{{url_fo…

设计模式(一)---简单工厂模式

1&#xff0c;简介&#xff1a;简单工厂模式&#xff0c;又称为静态工厂模式&#xff0c;是通过专门定义一个类来负责创建其他类的实例&#xff0c;被创建的实例通常都具有共同的父类。 2&#xff0c;简单工厂模式的结构 2.1&#xff1a;简单工厂的通用结构 2.2&#xff1a;示意…

给LaTex输出的论文PDF加上电子签名

目录问题准备签名插入签名TeXstudio 4.2.3 Windows 10 20H2 参考资料&#xff1a;研究生毕业论文电子签名怎么弄&#xff1f;—— kk肥妹 问题 完成论文之后&#xff0c;需要加上签名&#xff0c;但LaTex输出的结果是PDF格式的 准备签名 准备自己的签名&#xff0c;比如直接…

asp.net模态窗口返回值

个人感觉模态窗口在做网站的时候&#xff0c;使用到的比较少&#xff0c;前段时间在做项目时要实现以模态窗口传值和接收返回值&#xff0c; 模态窗口传值实现比较简单&#xff0c;但是做好后发现在Chrome浏览器中接收不到返回值&#xff0c;修改好Chrome浏览器的问题后 大概过…