潍坊建设企业网站,羽毛球赛事在哪看,长沙有效的可以看的网站,2022百度seo最新规则目录创建ROS工作空间创建ROS功能包CSysFs方式#xff08;需root#xff09;源文件blink.cppgpiolib.cpp头文件gpiolib.hCMakeLists.txt运行代码调用shell命令方式#xff08;无需root#xff09;源文件blink.cppCMakeLists.txt运行代码平台#xff1a;华硕 Thinker Edge R…
目录创建ROS工作空间创建ROS功能包CSysFs方式需root源文件blink.cppgpiolib.cpp头文件gpiolib.hCMakeLists.txt运行代码调用shell命令方式无需root源文件blink.cppCMakeLists.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 roscppC
参考ROS 树莓派小车制作一 ——ROS “点灯” —— 支链 为了更具普适性这里使用自定义的源码来自SysFs方式下C语言控制GPIORK3399—— 姚家湾来点灯其它方式见【RK3399Pro学习笔记】十八、点亮LED灯python、C语言、bash
SysFs方式需root
源文件
cd ~/catkin_ws/src/ROS_Test_LED/srcblink.cpp
nano blink.cpp#include ros/ros.h
#include std_msgs/Bool.h#include iostream
#include ROS_Test_LED/gpiolib.hvoid blink_callback(const std_msgs::Bool::ConstPtr msg)
{gpio_export(73);if(msg-data1){gpio_write(73, 0);ROS_INFO(LED ON);}if(msg-data0){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 subn.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.hint 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(Couldnt open IRQ file);ret -1;}if (dir 2 gpiofd){if (3 ! write(gpiofd, high, 3)){perror(Couldnt set GPIO direction to out);ret -2;}}if (dir 1 gpiofd){if (3 ! write(gpiofd, out, 3)){perror(Couldnt set GPIO direction to out);ret -3;}}else if (gpiofd){if (2 ! write(gpiofd, in, 2)){perror(Couldnt 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(Couldnt 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 cant 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(Couldnt 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_LEDgpiolib.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.txtcmake_minimum_required(VERSION 3.0.2)
project(ROS_Test_LED)## Compile as C11, supported in ROS Kinetic and newer
# add_compile_options(-stdc11)## 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 CMakes 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 isnt 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 dont 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 1rostopic pub /led_blink std_msgs/Bool 0新建一个终端
rqt_graph调用shell命令方式无需root
源文件
cd ~/catkin_ws/src/ROS_Test_LED/srcblink.cpp
nano blink.cpp#include ros/ros.h
#include std_msgs/Bool.h#include iostream
#include stdlib.hvoid blink_callback(const std_msgs::Bool::ConstPtr msg)
{if(msg-data1){system(gpio write 8 0);ROS_INFO(LED ON);}if(msg-data0){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 subn.subscribe(led_blink,10,blink_callback);ros::spin();
}其中8为wiringPi的引脚编号可通过gpio readall命令查看
CMakeLists.txt
nano ~/catkin_ws/src/ROS_Test_LED/CMakeLists.txtcmake_minimum_required(VERSION 3.0.2)
project(ROS_Test_LED)## Compile as C11, supported in ROS Kinetic and newer
# add_compile_options(-stdc11)## 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 CMakes 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 isnt 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 dont 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 1rostopic pub /led_blink std_msgs/Bool 0新建一个终端
rqt_graph