9#include <sys/syscall.h>
11#include <std_msgs/Float32.h>
12#include <vmxpi_ros/Float.h>
18 VMXResourceHandle pwmgen_res_handle;
19 VMXResourcePortIndex res_port_index;
21 ros::Publisher servo_angle_pub;
22 ros::ServiceServer setangle;
24 double maxangle = 150, minangle = -150;
26 uint16_t mapAngle(
double angle);
27 uint8_t channel_index;
46 ServoROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel);
68 bool SetAngle(vmxpi_ros::Float::Request &req, vmxpi_ros::Float::Response &res);
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