|
i2cpwm_board
0.5.1
ROS Package for PCA9685 based 16 channel PWM Board with I2C Interface
|
Functions | |
| void | servos_absolute (const i2cpwm_board::ServoArray::ConstPtr &msg) |
| subscriber topic to move servos in a physical position More... | |
| void | servos_proportional (const i2cpwm_board::ServoArray::ConstPtr &msg) |
| subscriber topic to move servos in the range of ±1.0 More... | |
| void | servos_drive (const geometry_msgs::Twist::ConstPtr &msg) |
| subscriber topic to move servos based on a drive mode More... | |
| void servos_absolute | ( | const i2cpwm_board::ServoArray::ConstPtr & | msg | ) |
#include <src/i2cpwm_controller.cpp>
subscriber topic to move servos in a physical position
Subscriber for the servos_absolute topic which processes one or more servos and sets their physical pulse value.
When working with a continuous rotation servo, the topic is used to find the center position of a servo by sending successive values until a stopped position is identified. The topic is also used to find the range of a servo - the fastest forward and fasted reverse values. The difference between these two is the servo's range. Due to variences in servos, each will likely have a slightly different center value.
When working with a fixed 180 degree rotation servo, the topic is used to find the center position of a servo by sending successive values until a the desired middle is identified. The topic is also used to find the range of a servo - the maximum clockwise and anti clockwise positions. The difference between these two is the servo's range. If the servo rotates slightly more in one direction from center than the other, then '2X' the lesser value should be used as the range to preserve the middle stop position.
| msg | a 'ServoArray' message (array of one or more 'Servo') where the servo:value is the pulse position/speed |
i2cpwm_board::ServoArray
i2cpwm_board::Servo
Example
Definition at line 797 of file i2cpwm_controller.cpp.
| void servos_proportional | ( | const i2cpwm_board::ServoArray::ConstPtr & | msg | ) |
#include <src/i2cpwm_controller.cpp>
subscriber topic to move servos in the range of ±1.0
Subscriber for controlling servos using proportional values. This topic processes one or more servos and sets their physical pulse value based on each servos physical range proportional to a range of ±1.0.
When working with a continuous rotation servo, the topic is used to adjust the speed of the servo.
When working with a fixed 180 degree rotation servo, the topic is used to adjust the position of the servo.
This topic requires the use of the config_servos() service. Once the configuration of the servos - center position, direction of rotation, and PWM range - has been set, these data are to convert the proportional value to a physical PWM value specific to each servo.
| msg | a 'ServoArray' message (array of one or more 'Servo') where the servo:value is a relative position/speed |
i2cpwm_board::ServoArray Message
i2cpwm_board::Servo Message
Example
Definition at line 867 of file i2cpwm_controller.cpp.
| void servos_drive | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |
#include <src/i2cpwm_controller.cpp>
subscriber topic to move servos based on a drive mode
Subscriber for controlling a group of servos in concert based on a geometry_msgs::Twist message.
This topic requires the use the config_servos() service to configure the servos for proportional control and the use of the config_drive_mode() to speccify the desired type of drive and to assign individual servos to the positions in the drive system.
| msg | a geometry Twist message |
geometry_msgs::Twist
geometry_msgs::Vector3
Example
Definition at line 976 of file i2cpwm_controller.cpp.
1.8.11