git commit -m "first commit for v2"
This commit is contained in:
@@ -0,0 +1,53 @@
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(gpio_handling)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
message_generation
|
||||
roscpp
|
||||
std_msgs
|
||||
)
|
||||
|
||||
# add_message_files(
|
||||
# FILES
|
||||
# Message1.msg
|
||||
# Message2.msg
|
||||
# )
|
||||
|
||||
add_service_files(
|
||||
FILES
|
||||
gpio_set_config.srv
|
||||
gpio_get_config.srv
|
||||
gpio_set_pin.srv
|
||||
gpio_get_pin.srv
|
||||
)
|
||||
|
||||
generate_messages(
|
||||
DEPENDENCIES
|
||||
std_msgs
|
||||
custom_messages
|
||||
)
|
||||
|
||||
#catkin_package(
|
||||
# # INCLUDE_DIRS include
|
||||
# LIBRARIES gpio_handling
|
||||
# CATKIN_DEPENDS message_generation message_runtime roscpp std_msgs
|
||||
#)
|
||||
|
||||
include_directories( ${catkin_INCLUDE_DIRS} )
|
||||
|
||||
# Service Server
|
||||
add_executable(gpio_handler src/gpio_handler.cpp)
|
||||
add_dependencies(gpio_handler ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
target_link_libraries(gpio_handler ${catkin_LIBRARIES} )
|
||||
|
||||
install(TARGETS gpio_handler
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
||||
|
||||
install(DIRECTORY include/${PROJECT_NAME}/
|
||||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
||||
FILES_MATCHING PATTERN "*.h"
|
||||
PATTERN ".svn" EXCLUDE
|
||||
)
|
||||
@@ -0,0 +1,2 @@
|
||||
uint8[18] pin_config
|
||||
bool[18] pin_value
|
||||
34
Devices/Packages/sick_line_guidance/turtlebotDemo/gpio_handling/package.xml
Executable file
34
Devices/Packages/sick_line_guidance/turtlebotDemo/gpio_handling/package.xml
Executable file
@@ -0,0 +1,34 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>gpio_handling</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The gpio_handling package</description>
|
||||
<maintainer email="tsprifl@todo.todo">tsprifl</maintainer>
|
||||
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>roscpp</build_depend>
|
||||
<!--
|
||||
<build_depend>custom_messages</build_depend>
|
||||
-->
|
||||
<build_depend>message_generation</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<!--
|
||||
<build_export_depend>custom_messages</build_export_depend>
|
||||
-->
|
||||
<build_export_depend>message_generation</build_export_depend>
|
||||
<build_export_depend>std_msgs</build_export_depend>
|
||||
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>message_runtime</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
|
||||
|
||||
<export>
|
||||
</export>
|
||||
|
||||
</package>
|
||||
@@ -0,0 +1,82 @@
|
||||
#include "gpio_handler.h"
|
||||
|
||||
int main(int argc, char **argv) // node main function
|
||||
{
|
||||
ros::init(argc, argv, "gpio_handler"); // initialize node with given name
|
||||
ROS_INFO("Node %s started", ros::this_node::getName().c_str()); // print info to ros command line
|
||||
ros::NodeHandle nh; // init node handle
|
||||
|
||||
// init servive servers
|
||||
ros::ServiceServer set_config_server = nh.advertiseService("gpio_set_config", gpio_set_config);
|
||||
ROS_INFO("gpio set_config_server ready. Call it with: rosservice call %s", set_config_server.getService().c_str());
|
||||
|
||||
ros::ServiceServer get_config_server = nh.advertiseService("gpio_get_config", gpio_get_config);
|
||||
ROS_INFO("gpio get_config_server ready. Call it with: rosservice call %s", get_config_server.getService().c_str());
|
||||
|
||||
ros::ServiceServer set_server = nh.advertiseService("gpio_set_pin", gpio_set_pin);
|
||||
ROS_INFO("gpio set_server ready. Call it with: rosservice call %s", set_server.getService().c_str());
|
||||
|
||||
ros::ServiceServer get_server = nh.advertiseService("gpio_get_pin", gpio_get_pin);
|
||||
ROS_INFO("gpio get_server ready. Call it with: rosservice call %s", get_server.getService().c_str());
|
||||
|
||||
// init publisher and subscriber
|
||||
ros::Publisher set_publisher = nh.advertise<custom_messages::gpio>("/gpio_set", 1, false);
|
||||
ros::Subscriber get_subscriber = nh.subscribe("/gpio_get", 1, gpioCallback);
|
||||
|
||||
/* gpio-message default values */
|
||||
for (int i = 0; i <= 17; i++)
|
||||
{
|
||||
gpio_set_msg.pin_config[i] = 4; //input pulldown (high impedance)
|
||||
gpio_set_msg.pin_value[i] = 0;
|
||||
gpio_get_msg.pin_value[i] = 4;
|
||||
gpio_get_msg.pin_value[i] = 0;
|
||||
}
|
||||
|
||||
ros::Rate loop_rate(200); // publish message rate = 200 Hz
|
||||
|
||||
while(ros::ok())
|
||||
{
|
||||
ros::spinOnce(); // handle service requests and subscriber callbacks
|
||||
set_publisher.publish(gpio_set_msg); // publish messages
|
||||
loop_rate.sleep(); // sleep for loop_rate
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
void gpioCallback(const custom_messages::gpioConstPtr &msg){
|
||||
gpio_get_msg = *msg;
|
||||
}
|
||||
|
||||
bool gpio_set_config(gpio_handling::gpio_set_config::Request &req, gpio_handling::gpio_set_config::Response &res){
|
||||
for(uint8_t i = 0; i < req.pinNumber.size(); i++)
|
||||
{
|
||||
gpio_set_msg.pin_config[req.pinNumber[i]] = req.pinMode[i];
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool gpio_get_config(gpio_handling::gpio_get_config::Request &req, gpio_handling::gpio_get_config::Response &res){
|
||||
res.pinMode.resize(req.pinNumber.size());
|
||||
for(uint8_t i = 0; i < req.pinNumber.size(); i++)
|
||||
{
|
||||
res.pinMode[i] = gpio_get_msg.pin_config[req.pinNumber[i]];
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool gpio_set_pin(gpio_handling::gpio_set_pin::Request &req, gpio_handling::gpio_set_pin::Response &res){
|
||||
for(uint8_t i = 0; i < req.pinNumber.size(); i++)
|
||||
{
|
||||
gpio_set_msg.pin_value[req.pinNumber[i]] = req.pinValue[i];
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool gpio_get_pin(gpio_handling::gpio_get_pin::Request &req, gpio_handling::gpio_get_pin::Response &res){
|
||||
res.pinValue.resize(req.pinNumber.size());
|
||||
for(uint8_t i = 0; i < req.pinNumber.size(); i++)
|
||||
{
|
||||
res.pinValue[i] = gpio_get_msg.pin_value[req.pinNumber[i]];
|
||||
}
|
||||
return true;
|
||||
}
|
||||
@@ -0,0 +1,19 @@
|
||||
#include "ros/ros.h"
|
||||
#include "custom_messages/gpio.h"
|
||||
#include "gpio_handling/gpio_set_config.h"
|
||||
#include "gpio_handling/gpio_get_config.h"
|
||||
#include "gpio_handling/gpio_set_pin.h"
|
||||
#include "gpio_handling/gpio_get_pin.h"
|
||||
#include <string>
|
||||
#include <iostream>
|
||||
|
||||
// messages for publish and subscribing for communication to openCR-board
|
||||
custom_messages::gpio gpio_set_msg;
|
||||
custom_messages::gpio gpio_get_msg;
|
||||
|
||||
// function Declaration
|
||||
void gpioCallback(const custom_messages::gpioConstPtr &msg);
|
||||
bool gpio_set_config(gpio_handling::gpio_set_config::Request &req, gpio_handling::gpio_set_config::Response &res);
|
||||
bool gpio_get_config(gpio_handling::gpio_get_config::Request &req, gpio_handling::gpio_get_config::Response &res);
|
||||
bool gpio_set_pin(gpio_handling::gpio_set_pin::Request &req, gpio_handling::gpio_set_pin::Response &res);
|
||||
bool gpio_get_pin(gpio_handling::gpio_get_pin::Request &req, gpio_handling::gpio_get_pin::Response &res);
|
||||
@@ -0,0 +1,3 @@
|
||||
uint8[] pinNumber
|
||||
---
|
||||
uint8[] pinMode
|
||||
@@ -0,0 +1,3 @@
|
||||
uint8[] pinNumber
|
||||
---
|
||||
bool[] pinValue
|
||||
@@ -0,0 +1,3 @@
|
||||
uint8[] pinNumber
|
||||
uint8[] pinMode
|
||||
---
|
||||
@@ -0,0 +1,3 @@
|
||||
uint8[] pinNumber
|
||||
bool[] pinValue
|
||||
---
|
||||
Reference in New Issue
Block a user