#include <ros/ros.h>
#include "kurt3d/ServoCommand.h"
#include <sensor_msgs/JointState.h>
#include <sstream>
#include "USBInterface.h"
#include <iostream>
#include <boost/thread.hpp>
Go to the source code of this file.
Defines | |
#define | _USE_MATH_DEFINES |
#define | RAD(GRAD) ((GRAD * (float)M_PI) / (float)180) |
#define | SERVO_MIN 1000 |
#define | SERVO_RANGE 1000 |
Functions | |
int | main (int argc, char **argv) |
void | moveServo (const sensor_msgs::JointState &req, bool secure) |
boost::mutex & | mut () |
bool | nod (kurt3d::ServoCommand::Request &req, kurt3d::ServoCommand::Response &res) |
void | servoCallback (const sensor_msgs::JointState::ConstPtr &req) |
void | setJointState (int channel, double angle) |
Variables | |
static sensor_msgs::JointState | currentState |
static std::string | jointNames [5] |
static double | max_pos [5] |
static double | min_pos [5] |
static ros::Publisher | state_pub |
#define _USE_MATH_DEFINES |
Definition at line 37 of file servo_node.cpp.
#define RAD | ( | GRAD | ) | ((GRAD * (float)M_PI) / (float)180) |
Definition at line 39 of file servo_node.cpp.
#define SERVO_MIN 1000 |
Definition at line 42 of file servo_node.cpp.
#define SERVO_RANGE 1000 |
Definition at line 41 of file servo_node.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 172 of file servo_node.cpp.
void moveServo | ( | const sensor_msgs::JointState & | req, |
bool | secure | ||
) |
Definition at line 86 of file servo_node.cpp.
boost::mutex& mut | ( | ) |
Definition at line 73 of file servo_node.cpp.
bool nod | ( | kurt3d::ServoCommand::Request & | req, |
kurt3d::ServoCommand::Response & | res | ||
) |
Definition at line 162 of file servo_node.cpp.
void servoCallback | ( | const sensor_msgs::JointState::ConstPtr & | req | ) |
Definition at line 155 of file servo_node.cpp.
void setJointState | ( | int | channel, |
double | angle | ||
) |
Definition at line 79 of file servo_node.cpp.
sensor_msgs::JointState currentState [static] |
Definition at line 46 of file servo_node.cpp.
std::string jointNames[5] [static] |
{ "drehobjekt_1_to_balken_1", "servo_1_a_to_wing_1_a", "servo_1_b_to_wing_1_b", "servo_2_a_to_wing_2_a", "servo_2_b_to_wing_2_b"}
Definition at line 65 of file servo_node.cpp.
double max_pos[5] [static] |
double min_pos[5] [static] |
ros::Publisher state_pub [static] |
Definition at line 44 of file servo_node.cpp.