#include <ros/ros.h>
#include "std_msgs/String.h"
#include "dynamixel_sdk_examples/GetPosition.h"
#include "dynamixel_sdk_examples/SetPosition.h"
#include "dynamixel_sdk/dynamixel_sdk.h"
Go to the source code of this file.
|
bool | getPresentPositionCallback (dynamixel_sdk_examples::GetPosition::Request &req, dynamixel_sdk_examples::GetPosition::Response &res) |
|
int | main (int argc, char **argv) |
|
void | setPositionCallback (const dynamixel_sdk_examples::SetPosition::ConstPtr &msg) |
|
◆ ADDR_GOAL_POSITION
#define ADDR_GOAL_POSITION 116 |
◆ ADDR_PRESENT_POSITION
#define ADDR_PRESENT_POSITION 132 |
◆ ADDR_TORQUE_ENABLE
#define ADDR_TORQUE_ENABLE 64 |
◆ BAUDRATE
◆ DEVICE_NAME
#define DEVICE_NAME "/dev/ttyUSB0" |
◆ DXL1_ID
◆ DXL2_ID
◆ PROTOCOL_VERSION
#define PROTOCOL_VERSION 2.0 |
◆ getPresentPositionCallback()
bool getPresentPositionCallback |
( |
dynamixel_sdk_examples::GetPosition::Request & |
req, |
|
|
dynamixel_sdk_examples::GetPosition::Response & |
res |
|
) |
| |
◆ main()
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
◆ setPositionCallback()
void setPositionCallback |
( |
const dynamixel_sdk_examples::SetPosition::ConstPtr & |
msg | ) |
|
◆ packetHandler
◆ portHandler