CMD Server for Marty, enabling execution of CMDs remotely. More...
#include <sys/socket.h>#include <netinet/in.h>#include <fcntl.h>#include <signal.h>#include "marty_msgs/Command.h"#include "marty_msgs/ServoMsg.h"#include "marty_msgs/ServoMsgArray.h"#include "ros_marty/marty_core.hpp"#include "ros_marty/trajectory.hpp"#include "std_msgs/Float32.h"#include "geometry_msgs/Pose2D.h"#include "marty_msgs/GPIOs.h"#include "marty_msgs/Accelerometer.h"#include "marty_msgs/MotorCurrents.h"

Go to the source code of this file.
Classes | |
| class | CmdServer |
Macros | |
| #define | PORT 1569 |
| #define | stop_wait 150 |
Enumerations | |
| enum | Axis { AXES_X = 0, AXES_Y, AXES_Z } |
| enum | Commands { CMD_HELLO = 0, CMD_MOVEJOINT, CMD_LEAN, CMD_WALK, CMD_EYES, CMD_KICK, CMD_LIFTLEG, CMD_LOWERLEG, CMD_CELEBRATE, CMD_DANCE, CMD_ROLLERSKATE, CMD_ARMS, CMD_DEMO, CMD_GET, CMD_SIDESTEP, CMD_STRAIGHT, CMD_SOUND, CMD_STOP } |
| enum | Direction { CMD_LEFT = 0, CMD_RIGHT, CMD_FORW, CMD_BACK } |
| Add new commands here for the server to receive. More... | |
| enum | Joint { J_HIP = 0, J_TWIST, J_KNEE, J_LEG, J_ARM, J_EYES } |
| enum | Sensors { GET_GPIO = 0, GET_ACCEL, GET_BATT, GET_CURR, GET_BALL } |
CMD Server for Marty, enabling execution of CMDs remotely.
Definition in file cmd_server.hpp.
| #define PORT 1569 |
Definition at line 32 of file cmd_server.hpp.
| #define stop_wait 150 |
Definition at line 35 of file cmd_server.hpp.
| enum Axis |
| Enumerator | |
|---|---|
| AXES_X | |
| AXES_Y | |
| AXES_Z | |
Definition at line 47 of file cmd_server.hpp.
| enum Commands |
Definition at line 62 of file cmd_server.hpp.
| enum Direction |
Add new commands here for the server to receive.
| Enumerator | |
|---|---|
| CMD_LEFT | |
| CMD_RIGHT | |
| CMD_FORW | |
| CMD_BACK | |
Definition at line 40 of file cmd_server.hpp.
| enum Joint |
| Enumerator | |
|---|---|
| J_HIP | |
| J_TWIST | |
| J_KNEE | |
| J_LEG | |
| J_ARM | |
| J_EYES | |
Definition at line 53 of file cmd_server.hpp.
| enum Sensors |
| Enumerator | |
|---|---|
| GET_GPIO | |
| GET_ACCEL | |
| GET_BATT | |
| GET_CURR | |
| GET_BALL | |
Definition at line 83 of file cmd_server.hpp.