Studica - Roscpp Documentation
VMX-pi ROS Library
Servo_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 <thread>
7#include <stdio.h>
8#include <unistd.h>
9#include <sys/syscall.h>
10
11#include <std_msgs/Float32.h>
12#include <vmxpi_ros/Float.h>
13
14class ServoROS : public Utils {
15 private:
16 VMXIO *io; // IO class of VMXPi
17
18 VMXResourceHandle pwmgen_res_handle;
19 VMXResourcePortIndex res_port_index;
20
21 ros::Publisher servo_angle_pub;
22 ros::ServiceServer setangle; // service to set the angle
23
24 double maxangle = 150, minangle = -150;
25
26 uint16_t mapAngle(double angle); // convert user's input of degrees into a value readable by the HAL
27 uint8_t channel_index;
28
29 double angle_ = 0;
30
31 std::thread runth;
32
33 public:
46 ServoROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel);
47
52 ~ServoROS();
53
68 bool SetAngle(vmxpi_ros::Float::Request &req, vmxpi_ros::Float::Response &res);
69
77 double GetAngle() const; // get current angle
78
86 double GetMinAngle() const; // get the servo's min angle
87
95 double GetMaxAngle() const; // get the servo's max angle
96
101 void Run_t();
102};
Definition: Servo_ros.h:14
double GetMaxAngle() const
Returns the maximum angle of the servo, which is 150deg.
Definition: Servo_ros.cpp:69
ServoROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel)
Constructs the ServoROS object on a specified channel index.
Definition: Servo_ros.cpp:21
~ServoROS()
Destructor for the ServoROS object.
Definition: Servo_ros.cpp:49
double GetAngle() const
Returns the current servo angle.
Definition: Servo_ros.cpp:52
double GetMinAngle() const
Returns the minimum angle of the servo, which is -150deg.
Definition: Servo_ros.cpp:67
bool SetAngle(vmxpi_ros::Float::Request &req, vmxpi_ros::Float::Response &res)
Converts user input of degrees into a value readable by the HAL.
Definition: Servo_ros.cpp:54
void Run_t()
Provides a method to call the various Services and Publishers of the ServoROS library advertising sen...
Definition: Servo_ros.cpp:71
Definition: vmxpi_utils.h:5