Studica - Roscpp Documentation
VMX-pi ROS Library
DO_ros.h
Go to the documentation of this file.
1#pragma once
2
3#include <ros/ros.h>
4#include "VMXPi.h"
5#include "vmxpi_utils.h"
6#include <std_srvs/Empty.h>
7#include <vmxpi_ros/Int.h>
8
9class DigitalOutputROS : public Utils {
10 private:
11 VMXIO *io; // IO class of the VMXPi
12 VMXTime *time; // Time class of the VMXPi
13 uint8_t channel_index;
14 uint32_t senduS;
15
16 VMXResourceHandle digitalout_res_handle;
17
18 // services to enable the ping loop and set the duration of the ping
19 ros::ServiceServer sendPing, setuS;
20 public:
33 DigitalOutputROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel);
34
48 // function to send a ping in 100ms intervals
49 bool Ping(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
50
63 // set the ping's duration
64 bool SetDuration(vmxpi_ros::Int::Request &req, vmxpi_ros::Int::Response &res);
65
66};
Definition: DO_ros.h:9
bool SetDuration(vmxpi_ros::Int::Request &req, vmxpi_ros::Int::Response &res)
Sets the duration of the ping signal.
Definition: DO_ros.cpp:36
DigitalOutputROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel)
Constructs the DigitalOutputROS object on a specified output channel index.
Definition: DO_ros.cpp:3
bool Ping(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Initiates a timed ultrasonic pulse on a DigitalIO Resource in Digital Output Mode in 0....
Definition: DO_ros.cpp:24
Definition: vmxpi_utils.h:5