diff --git a/bioloid_controller_cm510/CMakeLists.txt b/bioloid_controller_cm510/CMakeLists.txt index 6f0e39a9e57ea5f75bbf3c3901d0a08abc5966fd..fa6bf39ba2615ecf2daa71232e4856d423cc570e 100644 --- a/bioloid_controller_cm510/CMakeLists.txt +++ b/bioloid_controller_cm510/CMakeLists.txt @@ -124,7 +124,7 @@ add_library(${PROJECT_NAME} src/bioloid_controller_cm510.cpp ${BIOLOID_FW_PATH}/communications/src/dynamixel.c ${BIOLOID_FW_PATH}/communications/src/serial_console.c # main application module - ${BIOLOID_FW_PATH}/motion/src/examples/get_up.c + ${BIOLOID_FW_PATH}/motion/src/examples/walk_straight.c # AVR simulation modules src/sim/avr_delay.c src/sim/avr_registers.c diff --git a/bioloid_controller_cm510/include/bioloid_controller_cm510_impl.h b/bioloid_controller_cm510/include/bioloid_controller_cm510_impl.h index 2e6312ff728fe07039d4ba47ea28d539b165dc22..4078057bedcf0e93f2602c72f04f3db5549b5cd2 100644 --- a/bioloid_controller_cm510/include/bioloid_controller_cm510_impl.h +++ b/bioloid_controller_cm510/include/bioloid_controller_cm510_impl.h @@ -311,7 +311,7 @@ namespace bioloid_controller_cm510 init_leds(); init_buttons(); init_adc(); - exp_adc_init(); + exp_board_sim_init(); init_buzzer(); init_user_time(); /* call the user initialization function */ @@ -327,7 +327,7 @@ namespace bioloid_controller_cm510 real_angles[i]=joints_[i].getPosition(); pushbuttons_loop(); adc_loop(); - exp_adc_loop(); + exp_board_sim_loop(); buzzer_loop(); TIFR4|=(1<<OCF4A); manager_loop(); @@ -368,6 +368,8 @@ namespace bioloid_controller_cm510 } // process the compass information from the expansion board exp_compass_value=(tf::getYaw(msg->orientation)*180.0/3.14159)*10.0; + if(((int16_t)exp_compass_value)<0) + exp_compass_value+=3600; } template <class HardwareInterface> @@ -560,7 +562,6 @@ namespace bioloid_controller_cm510 this->exp_adc1_frame="none"; nh.getParam("exp_adc1_frame", this->exp_adc1_frame); ROS_DEBUG_STREAM_NAMED(name_, "Expansion board ADC1 associated to sensor: " << this->exp_adc1_frame); - std::cout << this->exp_adc1_frame << std::endl; this->exp_adc2_frame="none"; nh.getParam("exp_adc2_frame", this->exp_adc2_frame); ROS_DEBUG_STREAM_NAMED(name_, "Expansion board ADC2 associated to sensor: " << this->exp_adc2_frame); diff --git a/bioloid_controller_cm510/include/sim/exp_board_sim.h b/bioloid_controller_cm510/include/sim/exp_board_sim.h index 13663f9fe9b67e83d179c5c520c223a4ab0e69c6..d654a278c02e1728ab28bce064498f31257e84da 100644 --- a/bioloid_controller_cm510/include/sim/exp_board_sim.h +++ b/bioloid_controller_cm510/include/sim/exp_board_sim.h @@ -9,8 +9,8 @@ extern "C" { #define EXP_NUM_ADC 8 -void exp_adc_init(void); -void exp_adc_loop(void); +void exp_board_sim_init(void); +void exp_board_sim_loop(void); #ifdef __cplusplus }