/*
* File:
* Date:
* Description:
* Author:
* Modifications:
*/
/*
* You may need to add include files like or
* , etc.
*/
#include
/*
* You may want to add defines macro here.
*/
#define TIME_STEP 64
/*
* You should put some helper functions here
*/
/*
* This is the main program.
* The arguments of the main function can be specified by the
* "controllerArgs" field of the Robot node
*/
int main(int argc, char **argv)
{
/* necessary to initialize webots stuff */
wb_robot_init();
/*
* You should declare here DeviceTag variables for storing
* robot devices like this:
* WbDeviceTag my_sensor = wb_robot_get_device("my_sensor");
* WbDeviceTag my_actuator = wb_robot_get_device("my_actuator");
*/
/* main loop */
do {
/*
* Read the sensors :
* Enter here functions to read sensor data, like:
* double val = wb_distance_sensor_get_value(my_sensor);
*/
/* Process sensor data here */
/*
* Enter here functions to send actuator commands, like:
* wb_differential_wheels_set_speed(100.0,100.0);
*/
/*
* Perform a simulation step of 64 milliseconds
* and leave the loop when the simulation is over
*/
} while (wb_robot_step(TIME_STEP) != -1);
/* Enter here exit cleanup code */
/* Necessary to cleanup webots stuff */
wb_robot_cleanup();
return 0;
}
/*
* File: hexapod.c
* Date: September 22th, 2005
* Description: Alternate tripod gait using linear servos
* Author: Yvan Bourquin
* Modifications:Simon Blanchoud - September 12th, 2006
* Indentation of the code so that it follows the Webots Coding
* Standards
*
* Copyright (c) 2006 Cyberbotics - www.cyberbotics.com
*/
#include
#include
#include
#define TIME_STEP 16
#define NUM_SERVOS 12
#define NUM_STATES 6
#define FRONT +0.7
#define BACK -0.7
#define HI +0.02
#define LO -0.02
int main() {
const char *SERVO_NAMES[NUM_SERVOS] = {
"hip_servo_r0",
"hip_servo_r1",
"hip_servo_r2",
"hip_servo_l0",
"hip_servo_l1",
"hip_servo_l2",
"knee_servo_r0",
"knee_servo_r1",
"knee_servo_r2",
"knee_servo_l0",
"knee_servo_l1",
"knee_servo_l2"};
WbDeviceTag servos[NUM_SERVOS];
const double pos[NUM_STATES][NUM_SERVOS] = {
{BACK, FRONT, BACK, -FRONT, -BACK, -FRONT, LO, HI, LO, HI, LO, HI},
{BACK, FRONT, BACK, -FRONT, -BACK, -FRONT, HI, HI, HI, HI, HI, HI},
{BACK, FRONT, BACK, -FRONT, -BACK, -FRONT, HI, LO, HI, LO, HI, LO},
{FRONT, BACK, FRONT, -BACK, -FRONT, -BACK, HI, LO, HI, LO, HI, LO},
{FRONT, BACK, FRONT, -BACK, -FRONT, -BACK, HI, HI, HI, HI, HI, HI},
{FRONT, BACK, FRONT, -BACK, -FRONT, -BACK, LO, HI, LO, HI, LO, HI}
};
int elapsed = 0;
int state, i;
wb_robot_init();
for (i = 0; i < NUM_SERVOS; i++) {
servos[i] = wb_robot_get_device(SERVO_NAMES[i]);
if (!servos[i]) {
printf("could not find servo: %s\n",SERVO_NAMES[i]);
}
}
while(wb_robot_step(TIME_STEP)!=-1) {
elapsed++;
state = (elapsed / 25 + 1) % NUM_STATES;
for (i = 0; i < NUM_SERVOS; i++) {
wb_servo_set_position(servos[i], pos[state][i]);
}
}
wb_robot_cleanup();
return 0;
}
const char *SERVO_NAME = "servo";
WbDeviceTag servo;
servo = wb_robot_get_device(SERVO_NAME);
if (!servo) {
printf("could not find servo: %s\n",servo);
}
wb_servo_set_position(servo, INFINITY);
wb_servo_set_velocity(servo, 6.28); // 1 rotation per second