Skip to content
Snippets Groups Projects
Commit b7d9ad23 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Changed the GPIO interface to accomodate the changed in the firmware.

Removed the local copy of the dynamixel interface registers and used the firmware version.
parent 63eb7ea1
No related branches found
No related tags found
No related merge requests found
......@@ -13,7 +13,7 @@ INCLUDE (${PROJECT_SOURCE_DIR}/FindKDL.cmake)
# driver source files
SET(robot_sources darwin_robot.cpp darwin_robot_exceptions.cpp)
# application header files
SET(robot_headers darwin_robot.h darwin_robot_exceptions.h darwin_registers.h)
SET(robot_headers darwin_robot.h darwin_robot_exceptions.h)
# driver source files
SET(kin_sources darwin_arm_kinematics.cpp darwin_robot_exceptions.cpp)
......@@ -27,6 +27,7 @@ FIND_PACKAGE(dynamixel REQUIRED)
INCLUDE_DIRECTORIES(.)
INCLUDE_DIRECTORIES(${iriutils_INCLUDE_DIR})
INCLUDE_DIRECTORIES(${dynamixel_INCLUDE_DIR})
INCLUDE_DIRECTORIES(../../../stm32_firmware/include/)
# create the shared library
ADD_LIBRARY(darwin_robot SHARED ${robot_sources} ${XSD_SOURCES})
ADD_DEPENDENCIES(darwin_robot xsd_files_gen)
......
#ifndef _DARWIN_REGISTERS_
#define _DARWIN_REGISTERS_
#define MAX_NUM_SERVOS 27
typedef enum {
DARWIN_MODEL_NUMBER_L = 0x00,
DARWIN_MODEL_NUMBER_H = 0x01,
DARWIN_VERSION = 0x02,
DARWIN_ID = 0x03,
DARWIN_BAUD_RATE = 0x04,
DARWIN_RETURN_DELAY_TIME = 0x05,
DARWIN_MM_PERIOD_LOW = 0x06,
DARWIN_MM_PERIOD_HIGH = 0x07,
DARWIN_RETURN_LEVEL = 0x10,
DARWIN_DXL_POWER = 0x18,
DARWIN_LED_PANNEL = 0x19,
DARWIN_LED_5_L = 0x1A,
DARWIN_LED_5_H = 0x1B,
DARWIN_LED_6_L = 0x1C,
DARWIN_LED_6_H = 0x1D,
DARWIN_PUSHBUTTON = 0x1E,
DARWIN_MM_NUM_SERVOS = 0x1F,
DARWIN_MM_CONTROL = 0x20,
DARWIN_MM_STATUS = 0x21,
DARWIN_WALK_CONTROL = 0x22,
DARWIN_WALK_STATUS = 0x23,
DARWIN_IMU_CONTROL = 0x24,
DARWIN_IMU_STATUS = 0x25,
DARWIN_IMU_ACCEL_X_L = 0x26,
DARWIN_IMU_ACCEL_X_H = 0x27,
DARWIN_IMU_ACCEL_Y_L = 0x28,
DARWIN_IMU_ACCEL_Y_H = 0x29,
DARWIN_IMU_ACCEL_Z_L = 0x2A,
DARWIN_IMU_ACCEL_Z_H = 0x2B,
DARWIN_IMU_GYRO_X_L = 0x2C,
DARWIN_IMU_GYRO_X_H = 0x2D,
DARWIN_IMU_GYRO_Y_L = 0x2E,
DARWIN_IMU_GYRO_Y_H = 0x2F,
DARWIN_IMU_GYRO_Z_L = 0x30,
DARWIN_IMU_GYRO_Z_H = 0x31,
DARWIN_VOLTAGE = 0x32,
DARWIN_MIC1_L = 0x33,
DARWIN_MIC1_H = 0x34,
DARWIN_ADC2_L = 0x35,
DARWIN_ADC2_H = 0x36,
DARWIN_ADC3_L = 0x37,
DARWIN_ADC3_H = 0x38,
DARWIN_ADC4_L = 0x39,
DARWIN_ADC4_H = 0x3A,
DARWIN_ADC5_L = 0x3B,
DARWIN_ADC5_H = 0x3C,
DARWIN_ADC6_L = 0x3D,
DARWIN_ADC6_H = 0x3E,
DARWIN_ADC7_L = 0x3F,
DARWIN_ADC7_H = 0x40,
DARWIN_ADC8_L = 0x41,
DARWIN_ADC8_H = 0x42,
DARWIN_MIC2_L = 0x43,
DARWIN_MIC2_H = 0x44,
DARWIN_ADC10_L = 0x45,
DARWIN_ADC10_H = 0x46,
DARWIN_ADC11_L = 0x47,
DARWIN_ADC11_H = 0x48,
DARWIN_ADC12_L = 0x49,
DARWIN_ADC12_H = 0x4A,
DARWIN_ADC13_L = 0x4B,
DARWIN_ADC13_H = 0x4C,
DARWIN_ADC14_L = 0x4D,
DARWIN_ADC14_H = 0x4E,
DARWIN_ADC15_L = 0x4F,
DARWIN_ADC15_H = 0x50,
DARWIN_MM_MODULE_EN0 = 0x51,
DARWIN_MM_MODULE_EN1 = 0x52,
DARWIN_MM_MODULE_EN2 = 0x53,
DARWIN_MM_MODULE_EN3 = 0x54,
DARWIN_MM_MODULE_EN4 = 0x55,
DARWIN_MM_MODULE_EN5 = 0x56,
DARWIN_MM_MODULE_EN6 = 0x57,
DARWIN_MM_MODULE_EN7 = 0x58,
DARWIN_MM_MODULE_EN8 = 0x59,
DARWIN_MM_MODULE_EN9 = 0x5A,
DARWIN_MM_MODULE_EN10 = 0x5B,
DARWIN_MM_MODULE_EN11 = 0x5C,
DARWIN_MM_MODULE_EN12 = 0x5D,
DARWIN_MM_MODULE_EN13 = 0x5E,
DARWIN_MM_MODULE_EN14 = 0x5F,
DARWIN_MM_MODULE_EN15 = 0x60,
DARWIN_MM_SERVO0_CUR_POS_L = 0x61,
DARWIN_MM_SERVO0_CUR_POS_H = 0x62,
DARWIN_MM_SERVO1_CUR_POS_L = 0x63,
DARWIN_MM_SERVO1_CUR_POS_H = 0x64,
DARWIN_MM_SERVO2_CUR_POS_L = 0x65,
DARWIN_MM_SERVO2_CUR_POS_H = 0x66,
DARWIN_MM_SERVO3_CUR_POS_L = 0x67,
DARWIN_MM_SERVO3_CUR_POS_H = 0x68,
DARWIN_MM_SERVO4_CUR_POS_L = 0x69,
DARWIN_MM_SERVO4_CUR_POS_H = 0x6A,
DARWIN_MM_SERVO5_CUR_POS_L = 0x6B,
DARWIN_MM_SERVO5_CUR_POS_H = 0x6C,
DARWIN_MM_SERVO6_CUR_POS_L = 0x6D,
DARWIN_MM_SERVO6_CUR_POS_H = 0x6E,
DARWIN_MM_SERVO7_CUR_POS_L = 0x6F,
DARWIN_MM_SERVO7_CUR_POS_H = 0x70,
DARWIN_MM_SERVO8_CUR_POS_L = 0x71,
DARWIN_MM_SERVO8_CUR_POS_H = 0x72,
DARWIN_MM_SERVO9_CUR_POS_L = 0x73,
DARWIN_MM_SERVO9_CUR_POS_H = 0x74,
DARWIN_MM_SERVO10_CUR_POS_L = 0x75,
DARWIN_MM_SERVO10_CUR_POS_H = 0x76,
DARWIN_MM_SERVO11_CUR_POS_L = 0x77,
DARWIN_MM_SERVO11_CUR_POS_H = 0x78,
DARWIN_MM_SERVO12_CUR_POS_L = 0x79,
DARWIN_MM_SERVO12_CUR_POS_H = 0x7A,
DARWIN_MM_SERVO13_CUR_POS_L = 0x7B,
DARWIN_MM_SERVO13_CUR_POS_H = 0x7C,
DARWIN_MM_SERVO14_CUR_POS_L = 0x7D,
DARWIN_MM_SERVO14_CUR_POS_H = 0x7E,
DARWIN_MM_SERVO15_CUR_POS_L = 0x7F,
DARWIN_MM_SERVO15_CUR_POS_H = 0x80,
DARWIN_MM_SERVO16_CUR_POS_L = 0x81,
DARWIN_MM_SERVO16_CUR_POS_H = 0x82,
DARWIN_MM_SERVO17_CUR_POS_L = 0x83,
DARWIN_MM_SERVO17_CUR_POS_H = 0x84,
DARWIN_MM_SERVO18_CUR_POS_L = 0x85,
DARWIN_MM_SERVO18_CUR_POS_H = 0x86,
DARWIN_MM_SERVO19_CUR_POS_L = 0x87,
DARWIN_MM_SERVO19_CUR_POS_H = 0x88,
DARWIN_MM_SERVO20_CUR_POS_L = 0x89,
DARWIN_MM_SERVO20_CUR_POS_H = 0x8A,
DARWIN_MM_SERVO21_CUR_POS_L = 0x8B,
DARWIN_MM_SERVO21_CUR_POS_H = 0x8C,
DARWIN_MM_SERVO22_CUR_POS_L = 0x8D,
DARWIN_MM_SERVO22_CUR_POS_H = 0x8E,
DARWIN_MM_SERVO23_CUR_POS_L = 0x8F,
DARWIN_MM_SERVO23_CUR_POS_H = 0x90,
DARWIN_MM_SERVO24_CUR_POS_L = 0x91,
DARWIN_MM_SERVO24_CUR_POS_H = 0x92,
DARWIN_MM_SERVO25_CUR_POS_L = 0x93,
DARWIN_MM_SERVO25_CUR_POS_H = 0x94,
DARWIN_MM_SERVO26_CUR_POS_L = 0x95,
DARWIN_MM_SERVO26_CUR_POS_H = 0x96,
DARWIN_ACTION_PAGE = 0x97,
DARWIN_ACTION_CONTROL = 0x98,
DARWIN_ACTION_STATUS = 0x99,
DARWIN_X_OFFSET = 0x9A,
DARWIN_Y_OFFSET = 0x9B,
DARWIN_Z_OFFSET = 0x9C,
DARWIN_ROLL = 0x9D,
DARWIN_PITCH = 0x9E,
DARWIN_YAW = 0x9F,
DARWIN_HIP_PITCH_OFF_L = 0xA0,
DARWIN_HIP_PITCH_OFF_H = 0xA1,
DARWIN_PERIOD_TIME_L = 0xA2,
DARWIN_PERIOD_TIME_H = 0xA3,
DARWIN_DSP_RATIO = 0xA4,
DARWIN_STEP_FW_BW_RATIO = 0xA5,
DARWIN_STEP_FW_BW = 0xA6,
DARWIN_STEP_LEFT_RIGHT = 0xA7,
DARWIN_STEP_DIRECTION = 0xA8,
DARWIN_FOOT_HEIGHT = 0xA9,
DARWIN_SWING_RIGHT_LEFT = 0xAA,
DARWIN_SWING_TOP_DOWN = 0xAB,
DARWIN_PELVIS_OFFSET = 0xAC,
DARWIN_ARM_SWING_GAIN = 0xAD,
DARWIN_P_GAIN = 0xAE,
DARWIN_D_GAIN = 0xAF,
DARWIN_I_GAIN = 0xB0,
DARWIN_MAX_ACC = 0xB1,
DARWIN_MAX_ROT_ACC = 0xB2,
DARWIN_MM_KNEE_GAIN = 0xB3,
DARWIN_MM_ANKLE_PITCH_GAIN = 0xB4,
DARWIN_MM_HIP_ROLL_GAIN = 0xB5,
DARWIN_MM_ANKLE_ROLL_GAIN = 0xB6,
DARWIN_SERVO_0_SPEED = 0xB7,
DARWIN_SERVO_1_SPEED = 0xB8,
DARWIN_SERVO_2_SPEED = 0xB9,
DARWIN_SERVO_3_SPEED = 0xBA,
DARWIN_SERVO_4_SPEED = 0xBB,
DARWIN_SERVO_5_SPEED = 0xBC,
DARWIN_SERVO_6_SPEED = 0xBD,
DARWIN_SERVO_7_SPEED = 0xBE,
DARWIN_SERVO_8_SPEED = 0xBF,
DARWIN_SERVO_9_SPEED = 0xC0,
DARWIN_SERVO_10_SPEED = 0xC1,
DARWIN_SERVO_11_SPEED = 0xC2,
DARWIN_SERVO_12_SPEED = 0xC3,
DARWIN_SERVO_13_SPEED = 0xC4,
DARWIN_SERVO_14_SPEED = 0xC5,
DARWIN_SERVO_15_SPEED = 0xC6,
DARWIN_SERVO_16_SPEED = 0xC7,
DARWIN_SERVO_17_SPEED = 0xC8,
DARWIN_SERVO_18_SPEED = 0xC9,
DARWIN_SERVO_19_SPEED = 0xCA,
DARWIN_SERVO_20_SPEED = 0xCB,
DARWIN_SERVO_21_SPEED = 0xCC,
DARWIN_SERVO_22_SPEED = 0xCD,
DARWIN_SERVO_23_SPEED = 0xCE,
DARWIN_SERVO_24_SPEED = 0xCF,
DARWIN_SERVO_25_SPEED = 0xD0,
DARWIN_SERVO_26_SPEED = 0xD1,
DARWIN_SERVO_0_ACCEL = 0xD2,
DARWIN_SERVO_1_ACCEL = 0xD3,
DARWIN_SERVO_2_ACCEL = 0xD4,
DARWIN_SERVO_3_ACCEL = 0xD5,
DARWIN_SERVO_4_ACCEL = 0xD6,
DARWIN_SERVO_5_ACCEL = 0xD7,
DARWIN_SERVO_6_ACCEL = 0xD8,
DARWIN_SERVO_7_ACCEL = 0xD9,
DARWIN_SERVO_8_ACCEL = 0xDA,
DARWIN_SERVO_9_ACCEL = 0xDB,
DARWIN_SERVO_10_ACCEL = 0xDC,
DARWIN_SERVO_11_ACCEL = 0xDD,
DARWIN_SERVO_12_ACCEL = 0xDE,
DARWIN_SERVO_13_ACCEL = 0xDF,
DARWIN_SERVO_14_ACCEL = 0xE0,
DARWIN_SERVO_15_ACCEL = 0xE1,
DARWIN_SERVO_16_ACCEL = 0xE2,
DARWIN_SERVO_17_ACCEL = 0xE3,
DARWIN_SERVO_18_ACCEL = 0xE4,
DARWIN_SERVO_19_ACCEL = 0xE5,
DARWIN_SERVO_20_ACCEL = 0xE6,
DARWIN_SERVO_21_ACCEL = 0xE7,
DARWIN_SERVO_22_ACCEL = 0xE8,
DARWIN_SERVO_23_ACCEL = 0xE9,
DARWIN_SERVO_24_ACCEL = 0xEA,
DARWIN_SERVO_25_ACCEL = 0xEB,
DARWIN_SERVO_26_ACCEL = 0xEC,
DARWIN_JOINTS_CONTROL = 0xED,
DARWIN_JOINTS_STATUS = 0xEE,
DARWIN_HEAD_PAN_L = 0xEF,
DARWIN_HEAD_PAN_H = 0xF0,
DARWIN_HEAD_TILT_L = 0xF1,
DARWIN_HEAD_TILT_H = 0xF2,
DARWIN_HEAD_PAN_P = 0xF3,
DARWIN_HEAD_PAN_I = 0xF4,
DARWIN_HEAD_PAN_D = 0xF5,
DARWIN_HEAD_TILT_P = 0xF6,
DARWIN_HEAD_TILT_I = 0xF7,
DARWIN_HEAD_TILT_D = 0xF8,
DARWIN_HEAD_CONTROL = 0xF9,
DARWIN_HEAD_STATUS = 0xFA,
DARWIN_MM_CUR_PERIOD = 0xFB,
DARWIN_GRIPPER_CONTROL = 0xFC,
DARWIN_GRIPPER_STATUS = 0xFD,
DARWIN_GRIPPER_FORCE_LEFT = 0xFE,
DARWIN_GRIPPER_FORCE_RIGHT = 0xFF
} darwin_registers;
#endif
This diff is collapsed.
......@@ -2,41 +2,54 @@
#define _DARWIN_ROBOT_H
#include "dynamixel.h"
#include "dynamixelserver_ftdi.h"
#include "darwin_registers.h"
extern const std::string servo_names[MAX_NUM_SERVOS];
#define MAX_NUM_SERVOS 31
extern const std::string servo_names[MAX_NUM_SERVOS];
/* available motion modules */
typedef enum {DARWIN_MM_NONE=0x00,DARWIN_MM_ACTION=0x01,DARWIN_MM_WALKING=0x02,DARWIN_MM_JOINTS=0x03,DARWIN_MM_HEAD=0x04,DARWIN_MM_GRIPPER=0x05} mm_mode_t;
/* available grippers */
typedef enum {LEFT_GRIPPER=0,RIGHT_GRIPPER=1} grippers_t;
/* available leds */
#define GPIO_NUM_LEDS 11
typedef enum {LED_TX=0,LED_RX=1,LED_2=2,LED_3=3,LED_4=4,LED_5_R=5,LED_5_G=6,LED_5_B=7,LED_6_R=8,LED_6_G=9,LED_6_B=10} led_t;
typedef struct
{
unsigned short int control_reg;
unsigned short int data_reg;
unsigned char value_mask;
unsigned char toggle_mask;
unsigned char blink_mask;
}led_info_t;
/* available pushbuttons */
#define GPIO_NUM_PB 2
typedef enum {START_PB=0,MODE_PB=1} pushbutton_t;
class CDarwin_Robot
class CDarwinRobot
{
private:
CDynamixelServer *dyn_server;
CDynamixelServerFTDI *dyn_server;
CDynamixel *robot_device;
std::string robot_name;
unsigned char robot_id;
// GPIO variables
unsigned char current_led_value;
unsigned char current_pushbutton_value;
// motion manager variables
unsigned char num_servos;
public:
CDarwin_Robot(const std::string &name,std::string &bus_id,int bus_speed, unsigned char id);
CDarwinRobot(const std::string &name,std::string &bus_id,int bus_speed, unsigned char id);
// GPIO interface
void set_TxD_LED(void);
void clear_TxD_LED(void);
void set_RxD_LED(void);
void clear_RxD_LED(void);
void set_LED2(void);
void clear_LED2(void);
void set_LED3(void);
void clear_LED3(void);
void set_LED4(void);
void clear_LED4(void);
bool is_mode_button_pressed(void);
bool is_start_button_pressed(void);
void gpio_set_led(led_t led);
void gpio_clear_led(led_t led);
void gpio_toggle_led(led_t led);
void gpio_blink_led(led_t led, int period_ms);
void gpio_aux1_color(double red, double green, double blue);
void gpio_aux2_color(double red, double green, double blue);
bool is_button_pressed(pushbutton_t pushbutton);
// motion manager interface
void mm_set_period(double period_ms);
double mm_get_period(void);
......@@ -100,7 +113,7 @@ class CDarwin_Robot
// gripper interface
void gripper_open(grippers_t gripper);
void gripper_close(grippers_t gripper);
~CDarwin_Robot();
~CDarwinRobot();
};
#endif
# create an example application
ADD_EXECUTABLE(darwin_robot_test darwin_robot_test.cpp)
#ADD_EXECUTABLE(darwin_robot_test darwin_robot_test.cpp)
# link necessary libraries
TARGET_LINK_LIBRARIES(darwin_robot_test darwin_robot)
#TARGET_LINK_LIBRARIES(darwin_robot_test darwin_robot)
# create an example application
ADD_EXECUTABLE(darwin_joint_motion_test darwin_joint_motion_test.cpp)
ADD_EXECUTABLE(darwin_gpio_test darwin_gpio_test.cpp)
# link necessary libraries
TARGET_LINK_LIBRARIES(darwin_joint_motion_test darwin_robot)
TARGET_LINK_LIBRARIES(darwin_gpio_test darwin_robot)
# create an example application
ADD_EXECUTABLE(darwin_action_test darwin_action_test.cpp)
#ADD_EXECUTABLE(darwin_joint_motion_test darwin_joint_motion_test.cpp)
# link necessary libraries
TARGET_LINK_LIBRARIES(darwin_action_test darwin_robot)
#TARGET_LINK_LIBRARIES(darwin_joint_motion_test darwin_robot)
# create an example application
ADD_EXECUTABLE(darwin_walking_test darwin_walking_test.cpp)
#ADD_EXECUTABLE(darwin_action_test darwin_action_test.cpp)
# link necessary libraries
TARGET_LINK_LIBRARIES(darwin_walking_test darwin_robot)
#TARGET_LINK_LIBRARIES(darwin_action_test darwin_robot)
# create an example application
ADD_EXECUTABLE(darwin_imu_test darwin_imu_test.cpp)
#ADD_EXECUTABLE(darwin_walking_test darwin_walking_test.cpp)
# link necessary libraries
TARGET_LINK_LIBRARIES(darwin_imu_test darwin_robot)
#TARGET_LINK_LIBRARIES(darwin_walking_test darwin_robot)
# create an example application
ADD_EXECUTABLE(darwin_head_tracking_test darwin_head_tracking_test.cpp)
#ADD_EXECUTABLE(darwin_imu_test darwin_imu_test.cpp)
# link necessary libraries
TARGET_LINK_LIBRARIES(darwin_head_tracking_test darwin_robot)
#TARGET_LINK_LIBRARIES(darwin_imu_test darwin_robot)
# create an example application
ADD_EXECUTABLE(darwin_kin darwin_kin.cpp)
#ADD_EXECUTABLE(darwin_head_tracking_test darwin_head_tracking_test.cpp)
# link necessary libraries
TARGET_LINK_LIBRARIES(darwin_kin darwin_arm_kinematics)
#TARGET_LINK_LIBRARIES(darwin_head_tracking_test darwin_robot)
# create an example application
ADD_EXECUTABLE(darwin_gripper_test darwin_gripper_test.cpp)
#ADD_EXECUTABLE(darwin_kin darwin_kin.cpp)
# link necessary libraries
TARGET_LINK_LIBRARIES(darwin_gripper_test darwin_robot)
#TARGET_LINK_LIBRARIES(darwin_kin darwin_arm_kinematics)
# create an example application
#ADD_EXECUTABLE(darwin_gripper_test darwin_gripper_test.cpp)
# link necessary libraries
#TARGET_LINK_LIBRARIES(darwin_gripper_test darwin_robot)
......@@ -10,7 +10,7 @@ int main(int argc, char *argv[])
int i=0,num_v1_servos,num_v2_servos;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
CDarwinRobot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
......
#include "darwin_robot.h"
#include "darwin_robot_exceptions.h"
#include <iostream>
//std::string robot_device="A603LOBS";
std::string robot_device="A4008atn";
int main(int argc, char *argv[])
{
try{
CDarwinRobot darwin("Darwin",robot_device,926100,0x02);
std::cout << "found darwin controller" << std::endl;
darwin.gpio_blink_led(LED_TX,1000);
darwin.gpio_blink_led(LED_RX,2000);
darwin.gpio_blink_led(LED_2,4000);
darwin.gpio_blink_led(LED_3,8000);
darwin.gpio_set_led(LED_4);
darwin.gpio_aux1_color(1.0,1.0,1.0);
darwin.gpio_aux2_color(0.5,0.5,0.5);
sleep(10);
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
......@@ -11,7 +11,7 @@ int main(int argc, char *argv[])
std::vector<double> angles;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
CDarwinRobot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
darwin.mm_enable_power();
......
......@@ -12,7 +12,7 @@ int main(int argc, char *argv[])
std::vector<double> angles,speeds,accels;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
CDarwinRobot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
......
......@@ -13,7 +13,7 @@ int main(int argc, char *argv[])
short int gyro_x,gyro_y,gyro_z;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
CDarwinRobot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
darwin.mm_enable_power();
......
......@@ -12,7 +12,7 @@ int main(int argc, char *argv[])
std::vector<double> angles,speeds,accels;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
CDarwinRobot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
darwin.mm_enable_power();
......
......@@ -13,7 +13,7 @@ int main(int argc, char *argv[])
std::vector<double> angles,speeds,accels;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
CDarwinRobot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_load_config(config_file);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment