Webots Reference Manual - chapter 9 - section 1

Webots Reference Manual


9.1 C++ API

The following tables describes the C++ classes and their functions.

#include <webots/Accelerometer.hpp>
class Accelerometer : public Device {
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   const double *getValues() const;
};

#include <webots/Camera.hpp>
class Camera : public Device {
   enum {COLOR, RANGE_FINDER, BOTH};
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   double getFov() const;
   virtual void setFov(double fov);
   int getWidth() const;
   int getHeight() const;
   double getNear() const;
   double getMaxRange() const;
   int getType() const;
   const unsigned char *getImage() const;
   static unsigned char imageGetRed(const unsigned char *image,
     int width, int x, int y);
   static unsigned char imageGetGreen(const unsigned char *image,
     int width, int x, int y);
   static unsigned char imageGetBlue(const unsigned char *image,
     int width, int x, int y);
   static unsigned char imageGetGrey(const unsigned char *image,
     int width, int x, int y);
   const float *getRangeImage() const;
   static float rangeImageGetDepth(const float *image,
     int width, int x, int y);
   int saveImage(const std::string &filename, int quality) const;
};

#include <webots/Compass.hpp>
class Compass : public Device {
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   const double *getValues() const;
};

#include <webots/Connector.hpp>
class Connector : public Device {
   virtual void enablePresence(int ms);
   virtual void disablePresence();
   int getPresence() const;
   virtual void lock();
   virtual void unlock();
};

#include <webots/Device.hpp>
class Device {
   const std::string &getName() const;
   int getType() const;
};

#include <webots/DifferentialWheels.hpp>
class DifferentialWheels : public Robot {
   DifferentialWheels();
   virtual ~DifferentialWheels();
   virtual void setSpeed(double left, double right);
   virtual void enableEncoders(int ms);
   virtual void disableEncoders();
   int getEncodersSamplingPeriod();
   double getLeftEncoder() const;
   double getRightEncoder() const;
   virtual void setEncoders(double left, double right);
};

#include <webots/Display.hpp>
class Display : public Device {
   enum {RGB, RGBA, ARGB, BGRA};
   int getWidth() const;
   int getHeight() const;
   virtual void setColor(int color);
   virtual void setAlpha(double alpha);
   virtual void setOpacity(double opacity);
   virtual void drawPixel(int x1, int y1);
   virtual void drawLine(int x1, int y1, int x2, int y2);
   virtual void drawRectangle(int x, int y, int width, int height);
   virtual void drawOval(int cx, int cy, int a, int b);
   virtual void drawPolygon(const int *x, const int *y, int size);
   virtual void drawText(const std::string &txt, int x, int y);
   virtual void fillRectangle(int x, int y, int width, int height);
   virtual void fillOval(int cx, int cy, int a, int b);
   virtual void fillPolygon(const int *x, const int *y, int size);
   ImageRef *imageCopy(int x, int y, int width, int height) const;
   virtual void imagePaste(ImageRef *ir, int x, int y);
   ImageRef *imageLoad(const std::string &filename) const;
   ImageRef *imageNew(int width, int height, const void *data, int format) const;
   void imageSave(ImageRef *ir, const std::string &filename) const;
   void imageDelete(ImageRef *ir) const;
};

#include <webots/DistanceSensor.hpp>
class DistanceSensor : public Device {
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   double getValue() const;
};

#include <webots/Emitter.hpp>
class Emitter : public Device {
   enum {CHANNEL_BROADCAST};
   virtual int send(const void *data, int size);
   int getChannel() const;
   virtual void setChannel(int channel);
   double getRange() const;
   virtual void setRange(double range);
   int getBufferSize() const;
};

#include <webots/Field.hpp>
class Field {
   enum { SF_BOOL, SF_INT32, SF_FLOAT, SF_VEC2F, SF_VEC3F, SF_ROTATION, SF_COLOR, SF_STRING, SF_NODE, MF, MF_INT32, MF_FLOAT, MF_VEC2F, MF_VEC3F, MF_COLOR, MF_STRING, MF_NODE };
   int getType() const;
   std::string getTypeName() const;
   int getCount() const;
   bool getSFBool() const;
   int getSFInt32() const;
   double getSFFloat() const;
   const double *getSFVec2f() const;
   const double *getSFVec3f() const;
   const double *getSFRotation() const;
   const double *getSFColor() const;
   std::string getSFString() const;
   Node *getSFNode() const;
   int getMFInt32(int index) const;
   double getMFFloat(int index) const;
   const double *getMFVec2f(int index) const;
   const double *getMFVec3f(int index) const;
   const double *getMFColor(int index) const;
   std::string getMFString(int index) const;
   Node *getMFNode(int index) const;
   void setSFBool(bool value);
   void setSFInt32(int value);
   void setSFFloat(double value);
   void setSFVec2f(const double values[2]);
   void setSFVec3f(const double values[3]);
   void setSFRotation(const double values[4]);
   void setSFColor(const double values[3]);
   void setSFString(const std::string &value);
   void setMFInt32(int index, int value);
   void setMFFloat(int index, double value);
   void setMFVec2f(int index, const double values[2]);
   void setMFVec3f(int index, const double values[3]);
   void setMFColor(int index, const double values[3]);
   void setMFString(int index, const std::string &value);
   void importMFNode(int position, const std::string &filename);
};

#include <webots/GPS.hpp>
class GPS : public Device {
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   const double *getValues() const;
};

#include <webots/Gyro.hpp>
class Gyro : public Device {
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   const double *getValues() const;
};

#include <webots/ImageRef.hpp>
class ImageRef {
};

#include <webots/InertialUnit.hpp>
class InertialUnit : public Device {
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   const double *getRollPitchYaw() const;
};

#include <webots/LED.hpp>
class LED : public Device {
   virtual void set(int value);
};

#include <webots/LightSensor.hpp>
class LightSensor : public Device {
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   double getValue() const;
};

#include <webots/utils/Motion.hpp>
class Motion {
   Motion(const std::string &fileName);
   virtual ~Motion();
   bool isValid() const;
   virtual void play();
   virtual void stop();
   virtual void setLoop(bool loop);
   virtual void setReverse(bool reverse);
   bool isOver() const;
   int getDuration() const;
   int getTime() const;
   virtual void setTime(int time);
};

#include <webots/Node.hpp>
class Node {
   enum { NO_NODE, APPEARANCE, BACKGROUND, BOX, COLOR, CONE,
   COORDINATE, CYLINDER, DIRECTIONAL_LIGHT, ELEVATION_GRID,
   EXTRUSION, FOG, GROUP, IMAGE_TEXTURE, INDEXED_FACE_SET,
   INDEXED_LINE_SET, MATERIAL, POINT_LIGHT, SHAPE, SPHERE,
   SPOT_LIGHT, SWITCH, TEXTURE_COORDINATE, TEXTURE_TRANSFORM,
   TRANSFORM, VIEWPOINT, WORLD_INFO, CAPSULE, PLANE, ROBOT,
   SUPERVISOR, DIFFERENTIAL_WHEELS, SOLID, PHYSICS, CAMERA_ZOOM,
   CHARGER, DAMPING, CONTACT_PROPERTIES, ACCELEROMETER,
   CAMERA, COMPASS, CONNECTOR, DISPLAY, DISTANCE_SENSOR,
   EMITTER, GPS,GYRO, LED, LIGHT_SENSOR, MICROPHONE, PEN,
   RADIO, RECEIVER, SERVO, SPEAKER, TOUCH_SENSOR };
   int getType() const;
   std::string getTypeName() const;
   Field *getField(const std::string &fieldName) const;
   const double *getPosition() const;
   const double *getOrientation() const;
};

#include <webots/Pen.hpp>
class Pen : public Device {
   virtual void write(bool write);
   virtual void setInkColor(int color, double density);
};

#include <webots/Receiver.hpp>
class Receiver : public Device {
   enum {CHANNEL_BROADCAST};
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   int getQueueLength() const;
   virtual void nextPacket();
   const void *getData() const;
   int getDataSize() const;
   double getSignalStrength() const;
   const double *getEmitterDirection() const;
   virtual void setChannel(int channel);
   int getChannel() const;
};

#include <webots/Robot.hpp>
class Robot {
   enum {MODE_SIMULATION, MODE_CROSS_COMPILATION,
   MODE_REMOTE_CONTROL};
   enum {KEYBOARD_END, KEYBOARD_HOME, KEYBOARD_LEFT,
   KEYBOARD_UP, KEYBOARD_RIGHT, KEYBOARD_DOWN,
   KEYBOARD_PAGEUP, KEYBOARD_PAGEDOWN,
   KEYBOARD_NUMPAD_HOME, KEYBOARD_NUMPAD_LEFT,
   KEYBOARD_NUMPAD_UP, KEYBOARD_NUMPAD_RIGHT,
   KEYBOARD_NUMPAD_DOWN, KEYBOARD_NUMPAD_END,
   KEYBOARD_KEY, KEYBOARD_SHIFT, KEYBOARD_CONTROL,
   KEYBOARD_ALT};
   Robot();
   virtual ~Robot();
   virtual int step(int ms);
   Accelerometer *getAccelerometer(const std::string &name);
   Camera *getCamera(const std::string &name);
   Compass *getCompass(const std::string &name);
   Connector *getConnector(const std::string &name);
   Display *getDisplay(const std::string &name);
   DistanceSensor *getDistanceSensor(const std::string &name);
   Emitter *getEmitter(const std::string &name);
   GPS *getGPS(const std::string &name);
   Gyro *getGyro(const std::string &name);
   InertialUnit *getInertialUnit(const std::string &name);
   LED *getLED(const std::string &name);
   LightSensor *getLightSensor(const std::string &name);
   Pen *getPen(const std::string &name);
   Receiver *getReceiver(const std::string &name);
   Servo *getServo(const std::string &name);
   TouchSensor *getTouchSensor(const std::string &name);
   virtual void batterySensorEnable(int ms);
   virtual void batterySensorDisable();
   int getBatterySensorSamplingPeriod();
   virtual double batterySensorGetValue();
   double getBasicTimeStep() const;
   int getMode() const;
   std::string getModel() const;
   std::string getName() const;
   std::string getProjectPath() const;
   bool getSynchronization() const;
   double getTime() const;
   virtual void keyboardEnable(int ms);
   virtual void keyboardDisable();
   virtual int keyboardGetKey();
};

#include <webots/Servo.hpp>
class Servo : public Device {
   virtual void setPosition(double position);
   virtual void setVelocity(double vel);
   virtual void setAcceleration(double force);
   virtual void setMotorForce(double motor_force);
   virtual void setControlP(double p);
   virtual void enablePosition(int ms);
   virtual void disablePosition();
   int getPositionSamplingPeriod();
   double getPosition() const;
   virtual void enableMotorForceFeedback(int ms);
   virtual void disableMotorForceFeedback();
   int getMotorForceFeedbackSamplingPeriod();
   double getMotorForceFeedback() const;
   virtual void setForce(double force);
};

#include <webots/Supervisor.hpp>
class Supervisor : public Robot {
   Supervisor();
   virtual ~Supervisor();
   void exportImage(const std::string &file, int quality) const;
   Node *getRoot();
   Node *getFromDef(const std::string &name);
   virtual void setLabel(int id, const std::string &label, double xpos, double ypos,
     double size, int color, double transparency);
   virtual void simulationQuit(int status);
   virtual void simulationRevert();
   virtual void simulationPhysicsReset();
   void startMovie(const std::string &file,
   int width, int height, int type, int quality) const;
   void stopMovie() const;
};

#include <webots/TouchSensor.hpp>
class TouchSensor : public Device {
   virtual void enable(int ms);
   virtual void disable();
   int getSamplingPeriod();
   double getValue() const;
   const double *getValues() const;
};

release 7.0.2
Copyright © 2012 Cyberbotics Ltd. All right reserved.