|
Studica - Roscpp Documentation
VMX-pi ROS Library
|
#include <Servo_ros.h>
Public Member Functions | |
| ServoROS (ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel) | |
| Constructs the ServoROS object on a specified channel index. More... | |
| ~ServoROS () | |
| Destructor for the ServoROS object. More... | |
| bool | SetAngle (vmxpi_ros::Float::Request &req, vmxpi_ros::Float::Response &res) |
| Converts user input of degrees into a value readable by the HAL. More... | |
| double | GetAngle () const |
| Returns the current servo angle. More... | |
| double | GetMinAngle () const |
| Returns the minimum angle of the servo, which is -150deg. More... | |
| double | GetMaxAngle () const |
| Returns the maximum angle of the servo, which is 150deg. More... | |
| void | Run_t () |
| Provides a method to call the various Services and Publishers of the ServoROS library advertising sensor data to the ROS Master node. More... | |
Public Member Functions inherited from Utils | |
| void | DisplayVMXError (VMXErrorCode vmxerr) |
| Displays the VMXError. More... | |
| ServoROS::ServoROS | ( | ros::NodeHandle * | nh, |
| VMXPi * | vmx, | ||
| uint8_t | channel | ||
| ) |
Constructs the ServoROS object on a specified channel index.
| nh | Internal reference to the ROS node that the program will use to interact with the ROS system. |
| vmx | VMX-pi parameter used to initialize the VMX-pi HAL. |
| channel | Parameter to specify the channel index. |
| ServoROS::~ServoROS | ( | ) |
Destructor for the ServoROS object.
| double ServoROS::GetAngle | ( | ) | const |
Returns the current servo angle.
| double ServoROS::GetMaxAngle | ( | ) | const |
Returns the maximum angle of the servo, which is 150deg.
| double ServoROS::GetMinAngle | ( | ) | const |
Returns the minimum angle of the servo, which is -150deg.
| void ServoROS::Run_t | ( | ) |
Provides a method to call the various Services and Publishers of the ServoROS library advertising sensor data to the ROS Master node.
| bool ServoROS::SetAngle | ( | vmxpi_ros::Float::Request & | req, |
| vmxpi_ros::Float::Response & | res | ||
| ) |
Converts user input of degrees into a value readable by the HAL.
NOTE: The output range is clamped to -150deg - 150deg.
| req | Float request service type defined in the Float.srv file. |
| res | Float response service type defined in the Float.srv file. |