Webots Reference Manual develop
Supervisor
A Supervisor is a special type of Robot which has additional powers.
In fact, any Robot can be turned into a supervisor when its field named supervisor
is set to TRUE.
A Supervisor can modify the environment by adding or removing nodes to the scene, it can change their properties by modifying the values of parameters in a programmatic way, allowing for instance to move or setup a robot a certain way, it can start the creation of movies, animations and, last but not least, thanks to its unlimited access it can be used to acquire measurements about the state of the simulation as well as track its evolution.
However, even a Supervisor cannot access the internal information and measurements of devices mounted on a different robot, such as camera images and distance sensor measurements.
Note: Note that in some special cases the Supervisor functions might return wrong values and it might not be possible to retrieve fields and nodes. This occurs when closing a world and quitting its controllers, i.e. reloading the current world, opening a new world, or closing Webots. In this case the return value will be a NULL pointer or a default value. For functions returning a string, an empty string is returned instead of a NULL pointer.
Index
- Supervisor Functions
- wb_supervisor_node_get_root
- wb_supervisor_node_get_self
- wb_supervisor_node_get_from_def
- wb_supervisor_node_get_from_id
- wb_supervisor_node_get_from_device
- wb_supervisor_node_get_selected
- wb_supervisor_node_get_def
- wb_supervisor_node_get_id
- wb_supervisor_node_get_parent_node
- wb_supervisor_node_is_proto
- wb_supervisor_node_get_proto
- wb_supervisor_node_get_from_proto_def
- wb_supervisor_node_get_type
- wb_supervisor_node_get_type_name
- wb_supervisor_node_get_base_type_name
- wb_supervisor_node_remove
- wb_supervisor_node_export_string
- wb_supervisor_node_get_field
- wb_supervisor_node_get_field_by_index
- wb_supervisor_node_get_number_of_fields
- wb_supervisor_node_get_base_node_field
- wb_supervisor_node_get_base_node_field_by_index
- wb_supervisor_node_get_number_of_base_node_fields
- wb_supervisor_node_get_position
- wb_supervisor_node_get_orientation
- wb_supervisor_node_get_pose
- wb_supervisor_node_enable_pose_tracking
- wb_supervisor_node_disable_pose_tracking
- wb_supervisor_node_get_center_of_mass
- wb_supervisor_node_get_contact_points
- wb_supervisor_node_enable_contact_points_tracking
- wb_supervisor_node_disable_contact_points_tracking
- wb_supervisor_node_get_static_balance
- wb_supervisor_node_get_velocity
- wb_supervisor_node_set_velocity
- wb_supervisor_node_save_state
- wb_supervisor_node_load_state
- wb_supervisor_node_reset_physics
- wb_supervisor_node_set_joint_position
- wb_supervisor_node_restart_controller
- wb_supervisor_node_move_viewpoint
- wb_supervisor_node_set_visibility
- wb_supervisor_node_add_force
- wb_supervisor_node_add_force_with_offset
- wb_supervisor_node_add_torque
- wb_supervisor_set_label
- wb_supervisor_simulation_quit
- wb_supervisor_simulation_get_mode
- wb_supervisor_simulation_set_mode
- wb_supervisor_simulation_reset
- wb_supervisor_simulation_reset_physics
- wb_supervisor_world_load
- wb_supervisor_world_save
- wb_supervisor_world_reload
- wb_supervisor_export_image
- wb_supervisor_movie_start_recording
- wb_supervisor_movie_stop_recording
- wb_supervisor_movie_is_ready
- wb_supervisor_movie_failed
- wb_supervisor_animation_start_recording
- wb_supervisor_animation_stop_recording
- wb_supervisor_field_get_name
- wb_supervisor_field_get_type
- wb_supervisor_field_get_type_name
- wb_supervisor_field_get_count
- wb_supervisor_field_get_actual_field
- wb_supervisor_field_enable_sf_tracking
- wb_supervisor_field_disable_sf_tracking
- wb_supervisor_field_get_sf_bool
- wb_supervisor_field_get_sf_int32
- wb_supervisor_field_get_sf_float
- wb_supervisor_field_get_sf_vec2f
- wb_supervisor_field_get_sf_vec3f
- wb_supervisor_field_get_sf_rotation
- wb_supervisor_field_get_sf_color
- wb_supervisor_field_get_sf_string
- wb_supervisor_field_get_sf_node
- wb_supervisor_field_get_mf_bool
- wb_supervisor_field_get_mf_int32
- wb_supervisor_field_get_mf_float
- wb_supervisor_field_get_mf_vec2f
- wb_supervisor_field_get_mf_vec3f
- wb_supervisor_field_get_mf_rotation
- wb_supervisor_field_get_mf_color
- wb_supervisor_field_get_mf_string
- wb_supervisor_field_get_mf_node
- wb_supervisor_field_set_sf_bool
- wb_supervisor_field_set_sf_int32
- wb_supervisor_field_set_sf_float
- wb_supervisor_field_set_sf_vec2f
- wb_supervisor_field_set_sf_vec3f
- wb_supervisor_field_set_sf_rotation
- wb_supervisor_field_set_sf_color
- wb_supervisor_field_set_sf_string
- wb_supervisor_field_set_mf_bool
- wb_supervisor_field_set_mf_int32
- wb_supervisor_field_set_mf_float
- wb_supervisor_field_set_mf_vec2f
- wb_supervisor_field_set_mf_vec3f
- wb_supervisor_field_set_mf_rotation
- wb_supervisor_field_set_mf_color
- wb_supervisor_field_set_mf_string
- wb_supervisor_field_insert_mf_bool
- wb_supervisor_field_insert_mf_int32
- wb_supervisor_field_insert_mf_float
- wb_supervisor_field_insert_mf_vec2f
- wb_supervisor_field_insert_mf_vec3f
- wb_supervisor_field_insert_mf_rotation
- wb_supervisor_field_insert_mf_color
- wb_supervisor_field_insert_mf_string
- wb_supervisor_field_remove_mf
- wb_supervisor_field_remove_sf
- wb_supervisor_field_import_mf_node_from_string
- wb_supervisor_field_import_sf_node_from_string
- wb_supervisor_proto_get_type_name
- wb_supervisor_proto_is_derived
- wb_supervisor_proto_get_parent
- wb_supervisor_proto_get_field
- wb_supervisor_proto_get_field_by_index
- wb_supervisor_proto_get_number_of_fields
- wb_supervisor_virtual_reality_headset_is_used
- wb_supervisor_virtual_reality_headset_get_position
- wb_supervisor_virtual_reality_headset_get_orientation
- Contact Point
Supervisor Functions
As for a regular Robot controller, the wb_robot_init
, wb_robot_step
, etc. functions must be used in a Supervisor controller.
wb_supervisor_node_get_root
wb_supervisor_node_get_self
wb_supervisor_node_get_from_def
wb_supervisor_node_get_from_id
wb_supervisor_node_get_from_device
wb_supervisor_node_get_selected
#include <webots/supervisor.h>
WbNodeRef wb_supervisor_node_get_root();
WbNodeRef wb_supervisor_node_get_self();
WbNodeRef wb_supervisor_node_get_from_def(const char *def);
WbNodeRef wb_supervisor_node_get_from_id(int id);
WbNodeRef wb_supervisor_node_get_from_device(WbDeviceTag tag);
WbNodeRef wb_supervisor_node_get_selected();
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
Node *getRoot();
Node *getSelf();
Node *getFromDef(const std::string &name);
Node *getFromId(int id);
Node *getFromDevice(const Device *device);
Node *getSelected();
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def getRoot(self):
def getSelf(self):
def getFromDef(self, name):
def getFromId(self, id):
def getFromDevice(self, device):
def getSelected(self):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public Node getRoot();
public Node getSelf();
public Node getFromDef(String name);
public Node getFromId(int id);
public Node getFromDevice(Device device);
public Node getSelected();
// ...
}
node = wb_supervisor_node_get_root()
node = wb_supervisor_node_get_self()
node = wb_supervisor_node_get_from_def('def')
node = wb_supervisor_node_get_from_id(id)
node = wb_supervisor_node_get_from_device(tag)
node = wb_supervisor_node_get_selected()
Description
get a handle to a node in the world
The wb_supervisor_node_get_from_def
function returns a handle to a node in the world from its DEF name.
The return value can be used for subsequent calls to functions which require a WbNodeRef
parameter.
If the requested node does not exist in the current world file or is an internal node of a PROTO, the function returns NULL.
If a handle to an internal node of a PROTO should be retrieved, the wb_supervisor_node_get_from_proto_def
should be used instead.
Note that in case of procedural PROTO nodes regeneration, nodes retrieved by wb_supervisor_node_get_from_proto_def
might become invalid as well as all the descendant nodes and fields.
In this case, after triggering the PROTO regeneration, the nodes and fields should be retrieved again using the Supervisor API functions.
It is possible to use dots (.) as scoping operator in the DEF parameter. Dots can be used when looking for a specific node path in the node hierarchy. For example:
WbNodeRef node = wb_supervisor_node_get_from_def("ROBOT.JOINT.SOLID");
This means that we are searching for a node named "SOLID" inside a node named "JOINT", inside a node named "ROBOT".
The wb_supervisor_node_get_from_id
function retrieves a handle to a node, but from its unique identifier (the id
parameter).
The function returns NULL if the given identifier doesn't match with any node of the current world.
It is recommended to use this function only when knowing formerly the identifier (rather than looping on this function to retrieve all the nodes of a world).
For example, when exporting an W3D file, its XML nodes are containing an id
attribute which matches with the unique identifier described here.
The wb_supervisor_node_get_from_device
function retrieves the node's handle for a Device object.
The wb_supervisor_node_get_root
function returns a handle to the root node which is actually a Group node containing all the nodes visible at the top level in the scene tree window of Webots.
Like any Group node, the root node has a MFNode field called "children" which can be parsed to read each node in the scene tree.
An example of such a usage is provided in the "supervisor.wbt" sample worlds (located in the "projects/samples/devices/worlds" directory of Webots.
The wb_supervisor_node_get_self
function returns a handle to the Robot node itself on which the controller is run.
This is a utility function that simplifies the task of retrieving the base node without having to define a DEF name for it.
The wb_supervisor_node_get_selected
function returns a handle to the currently selected node in the scene tree.
If no node is currently selected, the function returns NULL.
wb_supervisor_node_get_def
wb_supervisor_node_get_id
wb_supervisor_node_get_parent_node
wb_supervisor_node_is_proto
wb_supervisor_node_get_proto
wb_supervisor_node_get_from_proto_def
#include <webots/supervisor.h>
const char *wb_supervisor_node_get_def(WbNodeRef node);
int wb_supervisor_node_get_id(WbNodeRef node);
WbNodeRef wb_supervisor_node_get_parent_node(WbNodeRef node);
bool wb_supervisor_node_is_proto(WbNodeRef node);
WbProtoRef wb_supervisor_node_get_proto(WbNodeRef node);
WbNodeRef wb_supervisor_node_get_from_proto_def(WbNodeRef node, const char *def);
#include <webots/Node.hpp>
namespace webots {
class Node {
int getId() const;
std::string getDef() const;
Node *getParentNode() const;
bool isProto() const;
Proto *getProto() const;
Node *getFromProtoDef(const std::string &name);
// ...
}
}
from controller import Node
class Node:
def getId(self):
def getDef(self):
def getParentNode(self):
def isProto(self):
def getProto(self):
def getFromProtoDef(self, name):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public int getId();
public String getDef();
public Node getParentNode();
public boolean isProto();
public Proto getProto();
public Node getFromProtoDef(String name);
// ...
}
id = wb_supervisor_node_get_id(node)
s = wb_supervisor_node_get_def(node)
node = wb_supervisor_node_get_parent_node(node)
b = wb_supervisor_node_is_proto(node)
proto = wb_supervisor_node_get_proto(node)
node = wb_supervisor_node_get_from_proto_def(node, 'def')
Description
get node info
The wb_supervisor_node_get_def
function retrieves the DEF name of the node passed as a parameter.
If no DEF name is specified, this function returns the empty string.
The wb_supervisor_node_get_id
function retrieves the unique identifier of the node given in parameter.
The wb_supervisor_node_get_parent_node
function retrieves the reference to the direct parent node of the node given in parameter.
The wb_supervisor_node_get_proto
function the instance of the proto type corresponding to the given node.
If the node is not a PROTO node, the function returns NULL.
The wb_supervisor_node_is_proto
function returns true
if the node given in the argument is a PROTO node.
The wb_supervisor_node_get_from_proto_def
function returns a handle to a node defined in the PROTO body of the specified node from its DEF name.
Note that this function works only for PROTO nodes.
wb_supervisor_node_get_type
wb_supervisor_node_get_type_name
wb_supervisor_node_get_base_type_name
#include <webots/supervisor.h>
#include <webots/node.h>
typedef enum {
WB_NODE_NO_NODE,
/* 3D rendering */
WB_NODE_APPEARANCE,
WB_NODE_BACKGROUND,
WB_NODE_BILLBOARD,
WB_NODE_BOX,
WB_NODE_CAD_SHAPE,
WB_NODE_CAPSULE,
WB_NODE_COLOR,
WB_NODE_CONE,
WB_NODE_COORDINATE,
WB_NODE_CYLINDER,
WB_NODE_DIRECTIONAL_LIGHT,
WB_NODE_ELEVATION_GRID,
WB_NODE_FOG,
WB_NODE_GROUP,
WB_NODE_IMAGE_TEXTURE,
WB_NODE_INDEXED_FACE_SET,
WB_NODE_INDEXED_LINE_SET,
WB_NODE_MATERIAL,
WB_NODE_MESH,
WB_NODE_MUSCLE,
WB_NODE_NORMAL,
WB_NODE_PBR_APPEARANCE,
WB_NODE_PLANE,
WB_NODE_POINT_LIGHT,
WB_NODE_POINT_SET,
WB_NODE_POSE,
WB_NODE_SHAPE,
WB_NODE_SPHERE,
WB_NODE_SPOT_LIGHT,
WB_NODE_TEXTURE_COORDINATE,
WB_NODE_TEXTURE_TRANSFORM,
WB_NODE_TRANSFORM,
WB_NODE_VIEWPOINT,
/* robots */
WB_NODE_ROBOT,
/* devices */
WB_NODE_ACCELEROMETER,
WB_NODE_ALTIMETER,
WB_NODE_BRAKE,
WB_NODE_CAMERA,
WB_NODE_COMPASS,
WB_NODE_CONNECTOR,
WB_NODE_DISPLAY,
WB_NODE_DISTANCE_SENSOR,
WB_NODE_EMITTER,
WB_NODE_GPS,
WB_NODE_GYRO,
WB_NODE_INERTIAL_UNIT,
WB_NODE_LED,
WB_NODE_LIDAR,
WB_NODE_LIGHT_SENSOR,
WB_NODE_LINEAR_MOTOR,
WB_NODE_PEN,
WB_NODE_POSITION_SENSOR,
WB_NODE_PROPELLER,
WB_NODE_RADAR,
WB_NODE_RANGE_FINDER,
WB_NODE_RECEIVER,
WB_NODE_ROTATIONAL_MOTOR,
WB_NODE_SKIN,
WB_NODE_SPEAKER,
WB_NODE_TOUCH_SENSOR,
WB_NODE_VACUUM_GRIPPER,
/* misc */
WB_NODE_BALL_JOINT,
WB_NODE_BALL_JOINT_PARAMETERS,
WB_NODE_CHARGER,
WB_NODE_CONTACT_PROPERTIES,
WB_NODE_DAMPING,
WB_NODE_FLUID,
WB_NODE_FOCUS,
WB_NODE_HINGE_JOINT,
WB_NODE_HINGE_JOINT_PARAMETERS,
WB_NODE_HINGE_2_JOINT,
WB_NODE_IMMERSION_PROPERTIES,
WB_NODE_JOINT_PARAMETERS,
WB_NODE_LENS,
WB_NODE_LENS_FLARE,
WB_NODE_PHYSICS,
WB_NODE_RECOGNITION,
WB_NODE_SLIDER_JOINT,
WB_NODE_SLOT,
WB_NODE_SOLID,
WB_NODE_SOLID_REFERENCE,
WB_NODE_TRACK,
WB_NODE_TRACK_WHEEL,
WB_NODE_WORLD_INFO,
WB_NODE_ZOOM
} WbNodeType;
WbNodeType wb_supervisor_node_get_type(WbNodeRef node);
const char *wb_supervisor_node_get_type_name(WbNodeRef node);
const char *wb_supervisor_node_get_base_type_name(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
typedef enum {
NO_NODE,
// 3D rendering
APPEARANCE, BACKGROUND, BILLBOARD, BOX, CAPSULE, COLOR, CONE, COORDINATE,
CYLINDER, DIRECTIONAL_LIGHT, ELEVATION_GRID, FOG, GROUP, IMAGE_TEXTURE,
INDEXED_FACE_SET, INDEXED_LINE_SET, MATERIAL, MESH, MUSCLE, NORMAL, PBR_APPEARANCE,
PLANE, POINT_LIGHT, POINT_SET, POSE, SHAPE, SPHERE, SPOT_LIGHT, TEXTURE_COORDINATE,
TEXTURE_TRANSFORM, TRANSFORM, VIEWPOINT,
// robots
ROBOT,
// devices
ACCELEROMETER, ALTIMETER, BRAKE, CAMERA, COMPASS, CONNECTOR, DISPLAY,
DISTANCE_SENSOR, EMITTER, GPS, GYRO, INERTIAL_UNIT, LED, LIDAR,
LIGHT_SENSOR, LINEAR_MOTOR, PEN, POSITION_SENSOR, PROPELLER,
RADAR, RANGE_FINDER, RECEIVER, ROTATIONAL_MOTOR, SKIN, SPEAKER, TOUCH_SENSOR,
VACUUM_GRIPPER,
// misc
BALL_JOINT, BALL_JOINT_PARAMETERS, CHARGER, CONTACT_PROPERTIES,
DAMPING, FLUID, FOCUS, HINGE_JOINT, HINGE_JOINT_PARAMETERS, HINGE_2_JOINT,
IMMERSION_PROPERTIES, JOINT_PARAMETERS, LENS, LENS_FLARE, PHYSICS, RECOGNITION,
SLIDER_JOINT, SLOT, SOLID, SOLID_REFERENCE, TRACK, TRACK_WHEEL, WORLD_INFO, ZOOM
} Type;
Type getType() const;
std::string getTypeName() const;
std::string getBaseTypeName() const;
// ...
}
}
from controller import Node
class Node:
NO_NODE,
# 3D rendering
APPEARANCE, BACKGROUND, BILLBOARD, BOX, CAPSULE, COLOR, CONE, COORDINATE,
CYLINDER, DIRECTIONAL_LIGHT, ELEVATION_GRID, FOG, GROUP, IMAGE_TEXTURE,
INDEXED_FACE_SET, INDEXED_LINE_SET, MATERIAL, MESH, MUSCLE, NORMAL, PBR_APPEARANCE,
PLANE, POINT_LIGHT, POINT_SET, POSE, SHAPE, SPHERE, SPOT_LIGHT, TEXTURE_COORDINATE,
TEXTURE_TRANSFORM, TRANSFORM, VIEWPOINT,
# robots
ROBOT,
# devices
ACCELEROMETER, ALTIMETER, BRAKE, CAMERA, COMPASS, CONNECTOR, DISPLAY,
DISTANCE_SENSOR, EMITTER, GPS, GYRO, INERTIAL_UNIT, LED, LIDAR,
LIGHT_SENSOR, LINEAR_MOTOR, PEN, POSITION_SENSOR, PROPELLER,
RADAR, RANGE_FINDER, RECEIVER, ROTATIONAL_MOTOR, SKIN, SPEAKER, TOUCH_SENSOR,
VACUUM_GRIPPER,
# misc
BALL_JOINT, BALL_JOINT_PARAMETERS, CHARGER, CONTACT_PROPERTIES,
DAMPING, FLUID, FOCUS, HINGE_JOINT, HINGE_JOINT_PARAMETERS, HINGE_2_JOINT,
IMMERSION_PROPERTIES, JOINT_PARAMETERS, LENS, LENS_FLARE, PHYSICS, RECOGNITION,
SLIDER_JOINT, SLOT, SOLID, SOLID_REFERENCE, TRACK, TRACK_WHEEL, WORLD_INFO, ZOOM
def getType(self):
def getTypeName(self):
def getBaseTypeName(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public final static int
NO_NODE,
// 3D rendering
APPEARANCE, BACKGROUND, BILLBOARD, BOX, CAPSULE, COLOR, CONE, COORDINATE,
CYLINDER, DIRECTIONAL_LIGHT, ELEVATION_GRID, FOG, GROUP, IMAGE_TEXTURE,
INDEXED_FACE_SET, INDEXED_LINE_SET, MATERIAL, MESH, MUSCLE, NORMAL, PBR_APPEARANCE,
PLANE, POINT_LIGHT, POINT_SET, POSE, SHAPE, SPHERE, SPOT_LIGHT, TEXTURE_COORDINATE,
TEXTURE_TRANSFORM, TRANSFORM, VIEWPOINT,
// robots
ROBOT,
// devices
ACCELEROMETER, ALTIMETER, BRAKE, CAMERA, COMPASS, CONNECTOR, DISPLAY,
DISTANCE_SENSOR, EMITTER, GPS, GYRO, INERTIAL_UNIT, LED, LIDAR,
LIGHT_SENSOR, LINEAR_MOTOR, PEN, POSITION_SENSOR, PROPELLER,
RADAR, RANGE_FINDER, RECEIVER, ROTATIONAL_MOTOR, SKIN, SPEAKER, TOUCH_SENSOR,
VACUUM_GRIPPER,
// misc
BALL_JOINT, BALL_JOINT_PARAMETERS, CHARGER, CONTACT_PROPERTIES,
DAMPING, FLUID, FOCUS, HINGE_JOINT, HINGE_JOINT_PARAMETERS, HINGE_2_JOINT,
IMMERSION_PROPERTIES, JOINT_PARAMETERS, LENS, LENS_FLARE, PHYSICS, RECOGNITION,
SLIDER_JOINT, SLOT, SOLID, SOLID_REFERENCE, TRACK, TRACK_WHEEL, WORLD_INFO, ZOOM;
public int getType();
public String getTypeName();
public String getBaseTypeName();
// ...
}
WB_NODE_NO_NODE,
% 3D rendering
WB_NODE_APPEARANCE, WB_NODE_BACKGROUND, WB_NODE_BILLBOARD, WB_NODE_BOX, WB_NODE_CAPSULE,
WB_NODE_COLOR, WB_NODE_CONE, WB_NODE_COORDINATE,
WB_NODE_CYLINDER, WB_NODE_DIRECTIONAL_LIGHT, WB_NODE_ELEVATION_GRID, WB_NODE_FOG,
WB_NODE_GROUP, WB_NODE_IMAGE_TEXTURE, WB_NODE_INDEXED_FACE_SET, WB_NODE_INDEXED_LINE_SET,
WB_NODE_MATERIAL, WB_NODE_MESH, WB_NODE_MUSCLE, WB_NODE_NORMAL,
WB_NODE_PBR_APPEARANCE, WB_NODE_PLANE, WB_NODE_POINT_LIGHT, WB_NODE_POINT_SET, WB_NODE_POSE,
WB_NODE_SHAPE, WB_NODE_SPHERE, WB_NODE_SPOT_LIGHT, WB_NODE_TEXTURE_COORDINATE,
WB_NODE_TEXTURE_TRANSFORM, WB_NODE_TRANSFORM, WB_NODE_VIEWPOINT,
% robots
WB_NODE_ROBOT,
% devices
WB_NODE_ACCELEROMETER, WB_NODE_ALTIMETER, WB_NODE_BRAKE, WB_NODE_CAMERA, WB_NODE_COMPASS,
WB_NODE_CONNECTOR, WB_NODE_DISPLAY, WB_NODE_DISTANCE_SENSOR, WB_NODE_EMITTER,
WB_NODE_GPS, WB_NODE_GYRO, WB_NODE_INERTIAL_UNIT, WB_NODE_LED, WB_NODE_LIDAR,
WB_NODE_LIGHT_SENSOR, WB_NODE_LINEAR_MOTOR, WB_NODE_PEN,
WB_NODE_POSITION_SENSOR, WB_NODE_PROPELLER, WB_NODE_RADAR,
WB_NODE_RANGE_FINDER, WB_NODE_RECEIVER, WB_NODE_ROTATIONAL_MOTOR,
WB_NODE_SKIN, WB_NODE_SPEAKER, WB_NODE_TOUCH_SENSOR, WB_NODE_VACUUM_GRIPPER,
% misc
WB_NODE_BALL_JOINT, WB_NODE_BALL_JOINT_PARAMETERS, WB_NODE_CHARGER,
WB_NODE_CONTACT_PROPERTIES, WB_NODE_DAMPING, WB_NODE_FLUID,
WB_NODE_FOCUS, WB_NODE_HINGE_JOINT, WB_NODE_HINGE_JOINT_PARAMETERS,
WB_NODE_HINGE_2_JOINT, WB_NODE_IMMERSION_PROPERTIES, WB_NODE_JOINT_PARAMETERS,
WB_NODE_LENS, WB_NODE_LENS_FLARE, WB_NODE_PHYSICS, WB_NODE_RECOGNITION,
WB_NODE_SLIDER_JOINT, WB_NODE_SLOT, WB_NODE_SOLID, WB_NODE_SOLID_REFERENCE,
WB_NODE_TRACK, WB_NODE_TRACK_WHEEL, WB_NODE_WORLD_INFO, WB_NODE_ZOOM
type = wb_supervisor_node_get_type(node)
name = wb_supervisor_node_get_type_name(node)
name = wb_supervisor_node_get_base_type_name(node)
Description
get information on a specified node
The wb_supervisor_node_get_type
function returns a symbolic value corresponding the type of the node specified as an argument.
If the argument is NULL, it returns WB_NODE_NO_NODE
.
A list of all node types is provided in the "webots/nodes.h" include file.
Node types include WB_NODE_APPEARANCE
, WB_NODE_LIGHT_SENSOR
, etc.
The wb_supervisor_node_get_type_name
function returns a text string corresponding to the name of the node.
If the argument node is a PROTO node, this function returns the PROTO name, like "E-puck", "RectangleArena", "Door", etc.
Otherwise if the argument node is not a PROTO node the returned value is the same as the output of wb_supervisor_node_get_base_type_name
function, i.e. "Robot", "Appearance", "LightSensor", etc.
If the argument is NULL, the function returns the empty string.
The wb_supervisor_node_get_base_type_name
function returns a text string corresponding to the base type name of the node, like "Robot", "Appearance", "LightSensor", etc.
If the argument is NULL, the function returns the empty string.
Note [C++, Java, Python]: In the oriented-object APIs, the
WB_NODE_*
constants are available as static integers of theNode
class (for example, Node::ROBOT). These integers can be directly compared with the output of theNode::getType
function.
wb_supervisor_node_remove
#include <webots/supervisor.h>
void wb_supervisor_node_remove(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
virtual void remove();
// ...
}
}
from controller import Node
class Node:
def remove(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public void remove();
// ...
}
wb_supervisor_node_remove(node)
Description
remove a specified node
The wb_supervisor_node_remove
function removes the node specified as an argument from the Webots scene tree.
If the node given in argument is the Robot node itself, it is removed only at the end of the step.
wb_supervisor_node_export_string
#include <webots/supervisor.h>
const char * wb_supervisor_node_export_string(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
std::string exportString() const;
// ...
}
}
from controller import Node
class Node:
def exportString(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public String exportString();
// ...
}
node_string = wb_supervisor_node_export_string(node)
Description
export a specified node
The wb_supervisor_node_export_string
function returns a string from which the node is constructed.
In conjunction with the wb_supervisor_field_import_sf/mf_node_from_string
functions it can be used to duplicate the node.
A file with the equivalent content can be produced in the Webots user interface by selecting the node in the scene tree window and using the Export
button.
wb_supervisor_node_get_field
wb_supervisor_node_get_field_by_index
wb_supervisor_node_get_number_of_fields
wb_supervisor_node_get_base_node_field
wb_supervisor_node_get_base_node_field_by_index
wb_supervisor_node_get_number_of_base_node_fields
#include <webots/supervisor.h>
WbFieldRef wb_supervisor_node_get_field(WbNodeRef node, const char *field_name);
WbFieldRef wb_supervisor_node_get_field_by_index(WbNodeRef node, int index);
int wb_supervisor_node_get_number_of_fields(WbNodeRef node);
WbFieldRef wb_supervisor_node_get_base_node_field(WbNodeRef node, const char *field_name);
WbFieldRef wb_supervisor_node_get_base_node_field_by_index(WbNodeRef node, int index);
int wb_supervisor_node_get_number_of_base_node_fields(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
Field *getField(const std::string &fieldName) const;
Field *getFieldByIndex(int index) const;
int getNumberOfFields() const;
Field *getBaseNodeField(const std::string &fieldName) const;
Field *getBaseNodeFieldByIndex(int index) const;
int getNumberOfBaseNodeFields() const;
// ...
}
}
from controller import Node
class Node:
def getField(self, fieldName):
def getFieldByIndex(self, index):
def getNumberOfFields(self):
def getBaseNodeField(self, fieldName):
def getBaseNodeFieldByIndex(self, index):
def getNumberOfBaseNodeFields(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public Field getField(String fieldName);
public Field getFieldByIndex(int index);
public int getNumberOfFields();
public Field getBaseNodeField(String fieldName);
public Field getBaseNodeFieldByIndex(int index);
public int getNumberOfBaseNodeFields();
// ...
}
field = wb_supervisor_node_get_field(node, 'field_name')
field = wb_supervisor_node_get_field_by_index(node, index)
size = wb_supervisor_node_get_number_of_fields(node)
field = wb_supervisor_node_get_base_node_field(node, 'field_name')
field = wb_supervisor_node_get_base_node_field_by_index(node, index)
size = wb_supervisor_node_get_number_of_base_node_fields(node)
Description
get a field reference from a node
The wb_supervisor_node_get_field
function retrieves a handler to a node field in the scene tree.
The field is specified by its name in field_name
and the node
it belongs to.
It can be a single field (SF) or a multiple field (MF).
If no such field name exists for the specified node in the scene tree, the return value is NULL.
Otherwise, it returns a handler to a field.
Note: The
wb_supervisor_node_get_field
function will return a valid field handler if the field corresponding to the field name is an hidden field.
If a field is defined for the base (Webots) type of a node but does not appear in the scene tree due to being an internal field of a PROTO, the wb_supervisor_node_get_base_node_field
function can be used instead.
Field handlers can also be retrieved by index using the wb_supervisor_node_get_field_by_index
function where the field is specified by its index
and the the node
it belongs to.
Valid index
values should be positive and lower than the number of fields returned by wb_supervisor_node_get_number_of_fields
.
If the arguments are not valid, wb_supervisor_node_get_field_by_index
returns NULL and wb_supervisor_node_get_number_of_fields
returns -1.
To retrieve an internal field of a PROTO, the wb_supervisor_node_get_base_node_field_by_index
and wb_supervisor_node_get_number_of_base_node_fields
should be used instead.
Note: fields retrieved with the
wb_supervisor_node_get_base_node_field
andwb_supervisor_node_get_base_node_by_index
functions are read-only. Which means that it is not possible to change them using any of thewb_supervisor_field_set_*
functions.
wb_supervisor_node_get_position
wb_supervisor_node_get_orientation
wb_supervisor_node_get_pose
wb_supervisor_node_enable_pose_tracking
wb_supervisor_node_disable_pose_tracking
#include <webots/supervisor.h>
const double *wb_supervisor_node_get_position(WbNodeRef node);
const double *wb_supervisor_node_get_orientation(WbNodeRef node);
const double *wb_supervisor_node_get_pose(WbNodeRef node, WbNodeRef from_node);
void wb_supervisor_node_enable_pose_tracking(WbNodeRef node, int sampling_period, WbNodeRef from_node);
void wb_supervisor_node_disable_pose_tracking(WbNodeRef node, WbNodeRef from_node);
#include <webots/Node.hpp>
namespace webots {
class Node {
const double *getPosition() const;
const double *getOrientation() const;
const double *getPose(const Node* fromNode = nullptr) const;
void enablePoseTracking(int samplingPeriod, const Node *fromNode = nullprt) const;
void disablePoseTracking(const Node *fromNode = nullptr) const;
// ...
}
}
from controller import Node
class Node:
def getPosition(self):
def getOrientation(self):
def getPose(self, fromNode=None):
def enablePoseTracking(self, samplingPeriod, fromNode=None):
def disablePoseTracking(self, fromNode=None):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public double[] getPosition();
public double[] getOrientation();
public double[] getPose(Node fromNode=null);
public void enablePoseTracking(int samplingPeriod, fromNode=null);
public void disablePoseTracking(fromNode=null);
// ...
}
position = wb_supervisor_node_get_position(node)
orientation = wb_supervisor_node_get_orientation(node)
pose = wb_supervisor_node_get_pose(node)
pose = wb_supervisor_node_get_pose(node, from_node)
wb_supervisor_node_enable_pose_tracking(sampling_period, node, from_node)
wb_supervisor_node_disable_pose_tracking(node, from_node)
Description
get the global (world) position/orientation of a node
The wb_supervisor_node_get_position
function returns the position of a node expressed in the global (world) coordinate system.
The node
argument must be a Pose node (or a derived node), otherwise the function will print a warning message and return 3 NaN
(Not a Number) values.
This function returns a vector containing exactly 3 values.
The wb_supervisor_node_get_orientation
function returns a matrix that represents the rotation of the node in the global (world) coordinate system.
The node
argument must be a Pose node (or a derived node), otherwise the function will print a warning message and return 9 NaN
(Not a Number) values.
This function returns a matrix containing exactly 9 values that shall be interpreted as a 3 x 3 orthogonal rotation matrix:
[ R[0] R[1] R[2] ]
[ R[3] R[4] R[5] ]
[ R[6] R[7] R[8] ]
Each column of the matrix represents where each of the three main axes (x, y and z) is pointing in the node's coordinate system. The columns (and the rows) of the matrix are pairwise orthogonal unit vectors (i.e., they form an orthonormal basis). Because the matrix is orthogonal, its transpose is also its inverse. So by transposing the matrix you can get the inverse rotation. Please find more info here.
By multiplying the rotation matrix on the right with a vector and then adding the position vector you can express the coordinates of a point in the global (world) coordinate system knowing its coordinates in a local (node) coordinate system. For example:
p' = R * p + T
Where p is a point whose coordinates are given with respect to the local coordinate system of a node, R the rotation matrix returned by the wb_supervisor_node_get_orientation
function, T is the position returned by the wb_supervisor_node_get_position
function and p' represents the same point but this time with coordinates expressed in the global (world) coordinate system.
The wb_supervisor_node_get_pose
function returns an array of 16 values.
The array shall be interpreted as a 4 x 4 transformation matrix that represents an absolute transform of the node.
The function returns the relative pose of the node with respect to the node specified in from_node
. If from_node
is null, it returns the absolute pose of the node in the global coordinate system.
The resulting matrix looks as following:
[ M[0] = R[0,0] M[1] = R[0,1] M[2] = R[0,2] M[3] = T[0] ]
[ M[4] = R[1,0] M[5] = R[1,1] M[6] = R[1,2] M[7] = T[1] ]
[ M[8] = R[2,0] M[9] = R[2,1] M[10] = R[2,2] M[11] = T[2]]
[ M[12] = 0 M[13] = 0 M[14] = 0 M[15] = 1 ]
Where M[i]
is the result of the wb_supervisor_node_get_pose
function at index i
.
The matrix is composed of a rotation matrix R
and a translation vector T
.
The wb_supervisor_node_enable_pose_tracking
function forces Webots to stream poses to the controller.
It improves the performance as the controller by default uses a request-response pattern to get pose data.
The sampling_period
argument determines how often the pose data should be sent to the controller.
Both the node
argument (or the node instance for C++, Python and Java) and the from_node
argument must be a Pose node (or a derived node).
If the from_node
argument is null or it is invalid, it returns the it returns the absolute pose of the node in the global coordinate system.
The wb_supervisor_node_disable_pose_tracking
function disables pose data tracking.
Both the node and the from_node
arguments should match the ones passed to the wb_supervisor_node_enable_pose_tracking
to successfully disable the tracking.
The "WEBOTS_HOME/projects/robots/neuronics/ipr/worlds/ipr_cube.wbt" simulation shows how to use these functions to achieve this (see the controller).
Note: The returned pointers are valid during one time step only as memory will be deallocated at the next time step.
wb_supervisor_node_get_center_of_mass
#include <webots/supervisor.h>
const double *wb_supervisor_node_get_center_of_mass(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
const double *getCenterOfMass() const;
// ...
}
}
from controller import Node
class Node:
def getCenterOfMass(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public double[] getCenterOfMass();
// ...
}
com = wb_supervisor_node_get_center_of_mass(node)
Description
get the global position of a solid's center of mass
The wb_supervisor_node_get_center_of_mass
function returns the position of the center of mass of a Solid node (including its descendant Solid nodes) expressed in the global (world) coordinate system.
The node
argument must be a Solid node (or a derived node), otherwise the function will print a warning message and return 3 NaN
(Not a Number) values.
This function returns a vector containing exactly 3 values.
If the node
argument has a NULL
physics
node, the return value is always the zero vector.
The "WEBOTS_HOME/projects/samples/howto/center_of_mass/worlds/center_of_mass.wbt" simulation shows how to use this function.
Note: The returned pointer is valid during one time step only as memory will be deallocated at the next time step.
wb_supervisor_node_get_contact_points
wb_supervisor_node_enable_contact_points_tracking
wb_supervisor_node_disable_contact_points_tracking
#include <webots/supervisor.h>
WbContactPoint *wb_supervisor_node_get_contact_points(WbNodeRef node, bool include_descendants, int *size);
wb_supervisor_node_enable_contact_points_tracking(WbNodeRef node, int sampling_period, bool include_descendants);
wb_supervisor_node_disable_contact_points_tracking(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
ContactPoint *getContactPoints(bool includeDescendants, int *size) const;
void enableContactPointsTracking(int samplingPeriod, bool includeDescendants = false) const;
void disableContactPointsTracking() const;
// ...
}
}
from controller import Node
class Node:
def getContactPoints(includeDescendants=False):
def enableContactPointsTracking(samplingPeriod, includeDescendants=False):
def disableContactPointsTracking():
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public ContactPoint[] getContactPoints(boolean includeDescendants);
public enableContactPointsTracking(int samplingPeriod, boolean includeDescendants = false);
public disableContactPointsTracking();
// ...
}
contact_point = wb_supervisor_node_get_contact_points(include_descendants):
wb_supervisor_node_enable_contact_points_tracking(sampling_period, include_descendants):
wb_supervisor_node_disable_contact_points_tracking():
Description
The wb_supervisor_node_get_contact_points
function returns a list of contact points of the given Solid
.
Contact points are expressed in the global (world) coordinate system.
The node
argument must be a Solid node (or a derived node), which moreover has no Solid
parent.
The include_descendants
argument defines whether the descendant nodes should also generate contact points or not.
The descendant nodes are the nodes included within the node given as an argument.
The size
argument is an output argument and it returns a number of contact points in the list.
The wb_supervisor_node_enable_contact_points_tracking
function forces Webots to stream contact points data to the controller.
It improves the performance as the controller by default uses a request-response pattern to get data from the field.
The sampling_period
argument determines how often the contact points data should be sent to the controller.
The wb_supervisor_node_disable_contact_points_tracking
function disables contact points data tracking.
The "WEBOTS_HOME/projects/samples/howto/cylinder_stack/worlds/cylinder_stack.wbt" project shows how to use this function.
Note: The returned pointer is valid during one time step only as memory will be deallocated at the next time step.
wb_supervisor_node_get_static_balance
#include <webots/supervisor.h>
bool wb_supervisor_node_get_static_balance(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
bool getStaticBalance() const;
// ...
}
}
from controller import Node
class Node:
def getStaticBalance(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public boolean getStaticBalance();
// ...
}
balance = wb_supervisor_node_get_static_balance(node)
Description
return the boolean value of the static balance test based on the support polygon of a solid
The wb_supervisor_node_get_static_balance
function returns the boolean value of the static balance test based on the support polygon of a solid.
The node
argument must be a Solid node (or a derived node), which moreover has no Solid
parent.
Otherwise the function will print a warning message and return false
.
The support polygon of a solid is the convex hull of the solid's contact points projected onto a plane that is orthognal to the gravity direction.
The test consists in checking whether the projection of the center of mass onto this plane lies inside or outside the support polygon.
wb_supervisor_node_get_velocity
wb_supervisor_node_set_velocity
#include <webots/supervisor.h>
const double *wb_supervisor_node_get_velocity(WbNodeRef node);
void wb_supervisor_node_set_velocity(WbNodeRef node, const double velocity[6]);
#include <webots/Node.hpp>
namespace webots {
class Node {
const double *getVelocity() const;
void setVelocity(const double velocity[6]);
// ...
}
}
from controller import Node
class Node:
def getVelocity(self):
def setVelocity(self, velocity):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public double[] getVelocity();
public void setVelocity(double velocity[6]);
// ...
}
velocity = wb_supervisor_node_get_velocity(node)
wb_supervisor_node_set_velocity(node, velocity)
Description
get/set the angular and linear velocities of a Solid node.
The wb_supervisor_node_get_velocity
function returns the absolute velocity (both linear and angular) of a node expressed in the global (world) coordinate system.
The node
argument must be a Solid node (or a derived node), otherwise the function will print a warning message and return 6 NaN
(Not a Number) values.
This function returns a vector containing exactly 6 values.
The first three are respectively the linear velocities in the x, y and z direction.
The last three are respectively the angular velocities around the x, y and z axes.
The wb_supervisor_node_set_velocity
function sets the absolute velocity (both linear and angular) of a node expressed in the global (world) coordinate system.
The node
argument must be a Solid node (or a derived node), otherwise the function will print a warning message and have no effect.
The velocity
argument must be a vector containing exactly 6 values.
The first three are respectively the linear velocities in the x, y and z direction.
The last three are respectively the angular velocities around the x, y and z axes.
wb_supervisor_node_save_state
wb_supervisor_node_load_state
wb_supervisor_node_reset_physics
#include <webots/supervisor.h>
void wb_supervisor_node_save_state(WbNodeRef node, const char *state_name);
void wb_supervisor_node_load_state(WbNodeRef node, const char *state_name);
void wb_supervisor_node_reset_physics(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
void saveState(const std::string &stateName);
void loadState(const std::string &stateName);
void resetPhysics();
// ...
}
}
from controller import Node
class Node:
def saveState(self, stateName):
def loadState(self, stateName):
def resetPhysics(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public void saveState(String stateName);
public void loadState(String stateName);
public void resetPhysics();
// ...
}
wb_supervisor_node_save_state(node, state_name)
wb_supervisor_node_load_state(node, state_name)
wb_supervisor_node_reset_physics(node)
Description
resets state of the given solid
The wb_supervisor_node_save_state
function saves the state of the given node and all its descendant nodes.
The state is saved internally under a key equal to the state_name
parameter.
Therefore, the state can be reverted using the wb_supervisor_node_load_state
function afterward.
Please refer to Reset/Reload Matrix for more details.
The wb_supervisor_node_load_state
function loads the state of the given node and all its descendant nodes.
The function parameter state_name
has to be a valid value, or the controller will fail.
The valid state_name
value means that the state is saved with the wb_supervisor_node_load_state
function, or a magic name __init__
.
The state in the beginning of the simulation is saved under the magic name __init__
.
The wb_supervisor_node_reset_physics
function stops the inertia of the given node and its descendants.
If the specified node is physics-enabled, i.e. it contains a Physics node, then the linear and angular velocities of the corresonding body are reset to 0, hence the inertia is also zeroed.
This function could be useful for resetting the physics of a solid after changing its translation or rotation.
To stop the inertia of all available solids please refer to this section.
wb_supervisor_node_set_joint_position
#include <webots/supervisor.h>
void wb_supervisor_node_set_joint_position(WbNodeRef node, double position, int index);
#include <webots/Node.hpp>
namespace webots {
class Node {
void setJointPosition(double position, int index = 1);
// ...
}
}
from controller import Node
class Node:
def setJointPosition(self, position, index=1):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public void setJointPosition(double position, int index);
// ...
}
wb_supervisor_node_set_joint_position(node, position, index)
Description
artificially sets the position of a joint
The wb_supervisor_node_set_joint_position
function artificially sets the position of an active or passive joint.
This function is particularly useful to programmatically setup the initial pose of a robot from a Supervisor controller since the position is changed immediately.
The node
argument, that has to be of Joint type, specifies which node is interested by the change and the position
argument specifies the new position of the joint.
Given that this is a generic function that handles all type of joints, the index
argument indicates the axis that should be modified.
Valid indices for each type of joint are listed in the following table.
Valid index value | Degrees of freedom | |
---|---|---|
SliderJoint | 1 | 1 |
HingeJoint | 1 | 1 |
Hinge2Joint | 1 or 2 | 2 |
BallJoint | 1, 2, or 3 | 3 |
wb_supervisor_node_restart_controller
#include <webots/supervisor.h>
void wb_supervisor_node_restart_controller(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
void restartController();
// ...
}
}
from controller import Node
class Node:
def restartController(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public void restartController();
// ...
}
wb_supervisor_node_restart_controller(node)
Description
restarts the controller of the given robot
The wb_supervisor_node_restart_controller
function restarts the controller of the Robot passed to it.
If a node other than a Robot is passed to this function, no change is effected, and a warning message is printed to the console.
Note that if a robot window is specified for the Robot node, the robot window will be restarted as well.
If an extern controller is used, then this function will only terminate the process, it will not start the controller again.
wb_supervisor_node_move_viewpoint
#include <webots/supervisor.h>
void wb_supervisor_node_move_viewpoint(WbNodeRef node);
#include <webots/Node.hpp>
namespace webots {
class Node {
void moveViewpoint() const;
// ...
}
}
from controller import Node
class Node:
def moveViewpoint(self):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public void moveViewpoint();
// ...
}
wb_supervisor_node_move_viewpoint(node)
Description
move the viewpoint to the node
The wb_supervisor_node_move_viewpoint
function moves the Viewpoint to the node given in argument.
Calling this function is equivalent to using the 'Move Viewpoint to Object' menu from the GUI.
wb_supervisor_node_set_visibility
#include <webots/supervisor.h>
void wb_supervisor_node_set_visibility(WbNodeRef node, WbNodeRef from, bool visible);
#include <webots/Node.hpp>
namespace webots {
class Node {
void setVisibility(Node *from, bool visible);
// ...
}
}
from controller import Node
class Node:
def setVisibility(self, from, visible):
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public void setVisibility(Node from, boolean visible);
// ...
}
wb_supervisor_node_set_visibility(node, from, visible)
Description
set the visibility of a node
The wb_supervisor_node_set_visibility
function sets the visibility of a node from the specified Camera, Lidar, RangeFinder or Viewpoint node.
In particular it defines if the node is visible in the image recorded by the from
device.
The from
argument must be either a Camera, Lidar, RangeFinder or Viewpoint node.
In case of the Viewpoint the node is hidden or shown in the main 3D scene.
The node
argument is the node to hide or show, if the node has some children they all will be recursively hidden too, any type of node is allowed but it doesn't make sense to hide a node that has no visual appearance in the 3D scene.
The visible
argument specifies whether the node should be hidden (false) or shown (true).
By default, all the nodes are visible.
It is relevant to show a node only if it was previously hidden using this function.
Note that this function cannot hide Fog and [Background][background.md] nodes. Additionally, the visibility of Propeller helices may be overridden internally by Webots when running the simulation or selecting them from the scene tree.
wb_supervisor_node_add_force
wb_supervisor_node_add_force_with_offset
wb_supervisor_node_add_torque
#include <webots/supervisor.h>
void wb_supervisor_node_add_force(WbNodeRef node, const double force[3], bool relative);
void wb_supervisor_node_add_force_with_offset(WbNodeRef node, const double force[3], const double offset[3], bool relative);
void wb_supervisor_node_add_torque(WbNodeRef node, const double torque[3], bool relative);
#include <webots/Node.hpp>
namespace webots {
class Node {
void addForce(const double force[3], bool relative);
void addForceWithOffset(const double force[3], const double offset[3], bool relative);
void addTorque(const double torque[3], bool relative);
// ...
}
}
from controller import Node
class Node:
def addForce(self, force, relative)
def addForceWithOffset(self, force, offset, relative)
def addTorque(self, torque, relative)
# ...
import com.cyberbotics.webots.controller.Node;
public class Node {
public void addForce(double force[3], boolean relative);
public void addForceWithOffset(double force[3], double offset[3], boolean relative);
public void addTorque(double torque[3], boolean relative);
// ...
}
void wb_supervisor_node_add_force(node, force, relative)
void wb_supervisor_node_add_force_with_offset(node, force, offset, relative)
void wb_supervisor_node_add_torque(node, torque, relative)
Description
add force or torque to a Solid node.
The wb_supervisor_node_add_force
function adds a force to the Solid node at its center of mass, the relative
argument defines if the force is expressed in world coordinate system (relative
set to false) or relatively to the node (relative
set to true).
The wb_supervisor_node_add_force_with_offset
function adds a force to the Solid node at the location (expressed in the node coordinate system) defined by the offset
argument.
The wb_supervisor_node_add_torque
function adds a torque to the Solid node.
wb_supervisor_set_label
#include <webots/supervisor.h>
void wb_supervisor_set_label(int id, const char *text, double x, double y, double size, int color, double transparency, const char *font);
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
virtual void setLabel(int id, const std::string &label, double xpos, double ypos,
double size, int color, double transparency = 0, const std::string &font = "Arial");
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def setLabel(self, id, label, x, y, size, color, transparency=0, font='Arial'):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public void setLabel(int id, String label, double xpos, double ypos,
double size, int color, double transparency = 0, String font = "Arial");
// ...
}
wb_supervisor_set_label(id, 'text', x, y, size, [r g b], transparency, font)
Description
overlay a text label on the 3D scene
The wb_supervisor_set_label
function displays a text label overlaying the 3D scene in Webots' main window.
The id
parameter is an identifier for the label; you can choose any value in the range 0 to 65534.
The same value may be used later if you want to change that label, or update the text.
Id value 65535 is reserved for automatic video caption.
The text
parameter is a text string which should contain only displayable characters in the range 32-127.
The x
and y
parameters are the coordinates of the upper left corner of the text, relative to the upper left corner of the 3D window.
These floating point values are expressed in percent of the 3D window width and height, hence, they should lie in the range 0-1.
The size
parameter defines the size of the font to be used.
It is expressed in the same unit as the y
parameter.
The color
parameter defines the color of the label.
It is expressed as a 3 bytes RGB integer, the most significant byte (leftmost byte in hexadecimal representation) represents the red component, the second most significant byte represents the green component and the third byte represents the blue component.
The transparency
parameter defines the transparency of the label.
A transparency level of 0 means no transparency, while a transparency level of 1 means total transparency (the text will be invisible).
Intermediate values correspond to semi-transparent levels.
Finally, the font
parameter defines the font used to draw the text, the following standard fonts are available:
- Arial
- Arial Black
- Comic Sans MS
- Courier New
- Georgia
- Impact
- Lucida Console
- Lucida Sans Unicode
- Palatino Linotype
- Tahoma
- Times New Roman
- Trebuchet MS
- Verdana
Examples
wb_supervisor_set_label(0,"hello world",0,0,0.1,0xff0000,0,"Arial");
This will display the label "hello world" in red at the upper left corner of the 3D window.
wb_supervisor_set_label(1,"hello Webots",0,0.1,0.1,0x00ff00,0.5,"Impact");
This will display the label "hello Webots" in semi-transparent green, just below.
supervisor_set_label(0,"hello universe",0,0,0.1,0xffff00,0,"Times New Roman");
This will change the label "hello world" defined earlier into "hello universe", using a yellow color for the new text.
Note [MATLAB]: In the MATLAB version of the
wb_supervisor_set_label
function, thecolor
argument must be a vector containing the three RGB components:[RED GREEN BLUE]
. Each component must be a value between 0.0 and 1.0. For example the vector[1 0 1]
represents the magenta color.
wb_supervisor_simulation_quit
#include <webots/supervisor.h>
void wb_supervisor_simulation_quit(int status);
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
virtual void simulationQuit(int status);
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def simulationQuit(self, status):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public void simulationQuit(int status);
// ...
}
wb_supervisor_simulation_quit(status)
Description
terminate the simulator and controller processes
The wb_supervisor_simulator_quit
function quits Webots, as if one was using the menu File / Quit Webots
.
This function makes it easier to invoke a Webots simulation from a script because it allows to terminate the simulation automatically, without human intervention.
As a result of quitting the simulator process, all controller processes, including the calling supervisor controller, will terminate.
The wb_supervisor_simulator_quit
function sends a request to quit the simulator and immediately returns to the controller process, it does not wait for the effective termination of the simulator.
After the call to the wb_supervisor_simulator_quit
function, the controller should call the wb_robot_cleanup
function and then exit.
The POSIX exit status returned by Webots can be defined by the status status
parameter.
Some typical values for this are the EXIT_SUCCESS
or EXIT_FAILURE
macros defined into the "stdlib.h" file.
Here is a C example:
#include <webots/robot.h>
#include <webots/supervisor.h>
#include <stdlib.h>
#define TIME_STEP 32
int main(int argc, char *argv[]) {
wb_robot_init();
...
while (! finished) {
// your controller code here
...
if (wb_robot_step(TIME_STEP) == -1)
break;
}
saveExperimentsData();
wb_supervisor_simulation_quit(EXIT_SUCCESS); // ask Webots to terminate
wb_robot_cleanup(); // cleanup resources
return 0;
}
In object-oriented languages, there is no wb_robot_cleanup
function, in this case the controller should call its destructor.
Here is a C++ example:
#include <webots/Robot.hpp>
#include <webots/Supervisor.hpp>
#include <cstdlib>
#define TIME_STEP 32
using namespace webots;
int main(int argc, char *argv[]) {
Supervisor *controller = new Supervisor();
...
while (! finished) {
// your controller code here
...
if (controller->step(TIME_STEP) == -1)
break;
}
controller->simulationQuit(EXIT_SUCCESS); // ask Webots to terminate
delete controller; // cleanup resources
return 0;
}
wb_supervisor_simulation_get_mode
wb_supervisor_simulation_set_mode
#include <webots/supervisor.h>
typedef enum {
WB_SUPERVISOR_SIMULATION_MODE_PAUSE,
WB_SUPERVISOR_SIMULATION_MODE_REAL_TIME,
WB_SUPERVISOR_SIMULATION_MODE_FAST
} WbSimulationMode;
WbSimulationMode wb_supervisor_simulation_get_mode();
void wb_supervisor_simulation_set_mode(WbSimulationMode mode);
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
typedef enum {
SIMULATION_MODE_PAUSE, SIMULATION_MODE_REAL_TIME, SIMULATION_MODE_FAST
} SimulationMode;
SimulationMode simulationGetMode() const;
virtual void simulationSetMode(SimulationMode mode);
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
SIMULATION_MODE_PAUSE, SIMULATION_MODE_REAL_TIME, SIMULATION_MODE_FAST
def simulationGetMode(self):
def simulationSetMode(self, mode):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public final static int SIMULATION_MODE_PAUSE, SIMULATION_MODE_REAL_TIME, SIMULATION_MODE_FAST;
public int simulationGetMode();
public void simulationSetMode(int mode);
// ...
}
WB_SUPERVISOR_SIMULATION_MODE_PAUSE, WB_SUPERVISOR_SIMULATION_MODE_REAL_TIME, WB_SUPERVISOR_SIMULATION_MODE_FAST
mode = wb_supervisor_simulation_get_mode()
wb_supervisor_simulation_set_mode(mode)
Description
get and set the simulation mode
The wb_supervisor_simulation_get_mode
function returns an integer matching with the current simulation mode, i.e., if the simulation is currently paused, is running in real-time, or in fast mode with or without the graphical renderings.
The macros described in the table are matching with the return value of this function.
The value returned by this function is updated during the previous function call of the wb_robot_init
or wb_robot_step
functions.
The wb_supervisor_simulation_set_mode
function allows to set the simulation mode.
Note that if the WB_SUPERVISOR_SIMULATION_MODE_PAUSE
is set by the current supervisor, then calling the wb_robot_step(time_step)
function with a time_step
argument different from 0 will make the controller wait until the simulation is resumed.
Calling wb_robot_step(0)
could be useful to send information to Webots when it is paused (such as modifying, moving, adding or deleting objects).
The simulation can then go on by calling for example wb_supervisor_simulation_set_mode(WB_SUPERVISOR_SIMULATION_MODE_FAST)
.
The current simulation mode can also be modified by the Webots user, when he's clicking on the corresponding buttons in the user interface.
Mode | Description |
---|---|
WB_SUPERVISOR_SIMULATION_MODE_PAUSE |
The simulation is paused. |
WB_SUPERVISOR_SIMULATION_MODE_REAL_TIME |
The simulation is running as close as possible to the real-time. |
WB_SUPERVISOR_SIMULATION_MODE_FAST |
The simulation is running as fast as possible without the graphical renderings. |
wb_supervisor_simulation_reset
#include <webots/supervisor.h>
void wb_supervisor_simulation_reset();
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
virtual void simulationReset();
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def simulationReset(self):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public void simulationReset();
// ...
}
wb_supervisor_simulation_reset()
Description
reset the simulation
The wb_supervisor_simulation_reset
function sends a request to the simulator process, asking it to reset the simulation at the end of the step.
The reset process is explained in detail in the User Guide, the only difference is that the supervisor and robot controllers are not restarted, if needed, they have to be restarted with the wb_supervisor_node_restart_controller
function.
You may wish to save some data in a file from your supervisor and robot controller programs in order to reload it when they restart.
Reset/Reload Matrix
The following table summarizes the behavior of different reset functions:
- Reload: The reload button in the user-interace and the
wb_supervisor_world_reload
funtion. - Reset from user interface: The reset button in the user-interace.
- Reset from Supervisor: The
wb_supervisor_simulation_reset
function. - Load node's state from Supervisor: The
wb_supervisor_node_save/load_state
functions. - Reset physics: The
wb_supervisor_simulation_reset_physics
function. - Reset node's physics: The
wb_supervisor_node_reset_physics
function.
Reload | Reset from user interface | Reset from Supervisor | Load node's state from Supervisor | Reset physics | Reset node's physics | |
---|---|---|---|---|---|---|
Resets simulation time | Yes | No | ||||
Removes nodes | Yes | No | ||||
Restarts controller | Yes | No | ||||
Stops sounds | Yes | No | ||||
Resets random seeds | Yes | No | ||||
Resets physics | Yes | Yes (scoped) | Yes | Yes (scoped) | ||
Resets physics plugin | Yes | No | ||||
Resets all fields | Yes | No | ||||
Adds removed nodes | Yes | No | ||||
Brake | Resets | Releases | N/A | |||
Charger | Resets | Resets the battery field and the emissiveColor field of the Material node of the first Shape child node |
Loads the battery field and resets the emissiveColor field of the Material node of the first Shape child node |
N/A | ||
Connector | Resets | Resets the isLocked field |
N/A | N/A | ||
Display | Resets | Clears | N/A | |||
Emitter/Receiver | Resets | Clears the message queue | N/A | |||
Joint/Motor | Resets | Resets the position, velocity, acceleration, available torque, and available force | Loads the position, resets the velocity, acceleration, available torque, and available force | N/A | ||
LED | Resets | If the first child is a Light node, it resets the color field and it switches the LED off.
If the first child is a Shape node, it resets the emissiveColor
field of its Material node. |
N/A | |||
Lidar | Resets | Resets the position of the rotating head | N/A | |||
Pen | Resets | Cleans the painted textures | N/A | |||
Propeller | Resets | Resets the slow helix and it's initial position | N/A | |||
Robot | Resets | Resets the battery field, removes all the supervisor labels, resets the nodes visibility,
and restarts the controller |
Loads the battery field, removes all the supervisor labels, and resets the nodes visibility
|
N/A | ||
Solid | Resets | Resets the translation and rotation fields, and the physics |
Loads the translation and rotation fields, and resets the physics |
N/A | ||
Track | Resets | Resets the motor position and the translation field of the textureTransform node of the Appearance node of the first Shape children node
|
Loads the motor position and the translation field of the textureTransform node of the Appearance node of the first Shape children node
|
N/A | ||
Viewpoint | Resets | Resets orientation , position , near , far , and
fieldOfView fields
|
Loads orientation , position , near , far , and
fieldOfView fields
|
N/A |
wb_supervisor_simulation_reset_physics
#include <webots/supervisor.h>
void wb_supervisor_simulation_reset_physics();
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
virtual void simulationResetPhysics();
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def simulationResetPhysics(self):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public void simulationResetPhysics();
// ...
}
wb_supervisor_simulation_reset_physics()
Description
stop the inertia of all solids in the world and reset the random number generator
The wb_supervisor_simulation_reset_physics
function sends a request to the simulator process, asking it to stop the movement of all physics-enabled solids in the world.
It means that for any Solid node containing a Physics node, the linear and angular velocities of the corresponding body are reset to 0, hence the inertia is also zeroed.
This is actually implemented by calling the ODE's dBodySetLinearVel
and dBodySetAngularVel
functions for all bodies with a zero velocity parameter.
This function is especially useful for resetting a robot to its initial position and inertia.
To stop the inertia of a single Solid node please refer to this section.
wb_supervisor_world_load
wb_supervisor_world_save
wb_supervisor_world_reload
#include <webots/supervisor.h>
void wb_supervisor_world_load(const char *filename);
bool wb_supervisor_world_save(const char *filename);
void wb_supervisor_world_reload();
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
virtual void worldLoad(const std::string &file);
virtual bool worldSave();
virtual bool worldSave(const std::string &file);
virtual void worldReload();
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def worldLoad(self, file):
def worldSave(self, file=None):
def worldReload(self):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public void worldLoad(String file);
public boolean worldSave();
public boolean worldSave(String file);
public void worldReload();
// ...
}
wb_supervisor_world_load('filename')
success = wb_supervisor_world_save()
success = wb_supervisor_world_save('filename')
wb_supervisor_world_reload()
Description
load, save or reload the current world.
The wb_supervisor_world_load
function sends a request to the simulator process, asking it to stop the current simulation and load the world given in argument immediately.
As a result of changing the current world, all the supervisor and robot controller processes are terminated and the new one are restarted with the new world.
You may wish to save some data in a file from your supervisor and robot controller programs in order to reload it from the new world.
The wb_supervisor_world_save
function saves the current world.
The filename
parameter defines the path to the target world file.
It should end with the .wbt
extension.
It can be defined either as an absolute path, or as a path relative to the current supervisor controller.
If NULL, the current world path is used instead (e.g., a simple save operation).
The boolean return value indicates the success of the save operation.
Be aware that this function can overwrite silently existing files, so that the corresponding data may be lost.
Note [C++, Java, Python, MATLAB]: Only for the C API it is required to pass NULL in order to perform a simple save operation. For all others the
Robot.worldSave
function can be called without argument.
The wb_supervisor_world_reload
function sends a request to the simulator process, asking it to reload the current world immediately.
As a result of reloading the current world, all the supervisor and robot controller processes are terminated and restarted.
You may wish to save some data in a file from your supervisor and robot controller programs in order to reload it when they restart.
wb_supervisor_export_image
#include <webots/supervisor.h>
void wb_supervisor_export_image(const char *filename, int quality);
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
void exportImage(const std::string &file, int quality) const;
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def exportImage(self, file, quality):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public void exportImage(String file, int quality);
// ...
}
wb_supervisor_export_image('filename', quality)
Description
save the current 3D image of the simulator into a JPEG file, suitable for building a webcam system
The wb_supervisor_export_image
function saves the current image of Webots main window into a JPEG file as specified by the filename
parameter.
If the target file exists, it will be silently overwritten.
The quality
parameter defines the JPEG quality (in the range 1 - 100).
The filename
parameter should specify a valid (absolute or relative) file name, e.g., "snapshot.jpg" or "/var/www/html/images/snapshot.jpg".
In fact, a temporary file is first saved, and then renamed to the requested filename
.
This avoids having a temporary unfinished (and hence corrupted) file for webcam applications.
wb_supervisor_movie_start_recording
wb_supervisor_movie_stop_recording
wb_supervisor_movie_is_ready
wb_supervisor_movie_failed
#include <webots/supervisor.h>
void wb_supervisor_movie_start_recording(const char *filename, int width, int height, int codec, int quality, int acceleration, bool caption);
void wb_supervisor_movie_stop_recording();
bool wb_supervisor_movie_is_ready();
bool wb_supervisor_movie_failed();
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
virtual void movieStartRecording(const std::string &file, int width, int height, int codec, int quality, int acceleration, bool caption) const;
virtual void movieStopRecording();
bool movieIsReady() const;
bool movieFailed() const;
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def movieStartRecording(self, file, width, height, codec, quality, acceleration, caption):
def movieStopRecording(self):
def movieIsReady(self):
def movieFailed(self):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public void movieStartRecording(String file, int width, int height, int codec, int quality, int acceleration, boolean caption);
public void movieStopRecording();
public boolean movieIsReady();
public boolean movieFailed();
// ...
}
wb_supervisor_movie_start_recording('filename', width, height, codec, quality,
acceleration, caption)
wb_supervisor_movie_stop_recording()
status = wb_supervisor_movie_is_ready()
status = wb_supervisor_movie_failed()
Description
export the current simulation into a movie file
The wb_supervisor_movie_start_recording
function starts saving the current simulation into a movie file.
The movie creation process will complete after the wb_supervisor_movie_stop_recording
function is called.
The movie is saved in the file defined by the filename
parameter.
If the filename
doesn't end with a ".mp4" extension, the file extension is completed automatically.
If the target file exists, it will be silently overwritten.
The codec
parameter specify the codec used when creating the movie.
Currently only MPEG-4/AVC encoding is available and the codec
value is ignored.
The quality
corresponds to the movie compression factor that affects the movie quality and file size.
It should be a value between 1 and 100.
Beware, that choosing a too small value may cause the video encoding program to fail because of a too low bitrate.
The movie frame rate is automatically computed based on the basicTimeStep
value of the simulation in order to produce a real-time movie.
The acceleration
specifies the acceleration factor of the created movie with respect to the real simulation time.
Default value is 1, i.e. no acceleration.
If caption
parameters is set to true, a default caption is printed on the top right corner of the movie showing the current acceleration
value.
The wb_supervisor_movie_is_ready
function returns true
if the application is ready to start recording a movie, i.e. if another recording process is not already running.
So it could be used to check if the encoding process is completed and the file has been created.
Note that if the recording process failed, this function will return true
.
In order to detect a failure the wb_supervisor_movie_failed
function has to be called.
The wb_supervisor_movie_failed
function returns true
if the recording process failed.
After starting a new recording process the returned value is reset to false
.
wb_supervisor_animation_start_recording
wb_supervisor_animation_stop_recording
#include <webots/supervisor.h>
bool wb_supervisor_animation_start_recording(const char *filename);
bool wb_supervisor_animation_stop_recording();
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
virtual bool animationStartRecording(const std::string &file);
virtual bool animationStopRecording();
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def animationStartRecording(self, file):
def animationStopRecording(self):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public boolean animationStartRecording(String file);
public boolean animationStopRecording();
// ...
}
success = wb_supervisor_animation_start_recording('filename')
success = wb_supervisor_animation_stop_recording()
Description
export the current simulation into an animation file
The wb_supervisor_animation_start_recording
function starts saving the current simulation into an animation file.
The animation creation process will complete after the wb_supervisor_animation_stop_recording
function is called.
Only one animation can be created at the same time.
The animation is saved in the file defined by the filename
parameter.
If the target file exists, it will be silently overwritten.
The filename
should ends with the ".html" extension.
The animation frame rate is automatically computed based on the basicTimeStep
value of the simulation in order to produce a real-time animation.
Both wb_supervisor_animation_start_recording
and wb_supervisor_animation_stop_recording
functions are returning a boolean indicating their success.
wb_supervisor_field_get_name
wb_supervisor_field_get_type
wb_supervisor_field_get_type_name
wb_supervisor_field_get_count
wb_supervisor_field_get_actual_field
wb_supervisor_field_enable_sf_tracking
wb_supervisor_field_disable_sf_tracking
#include <webots/supervisor.h>
typedef enum {
WB_NO_FIELD, WB_SF_BOOL, WB_SF_INT32, WB_SF_FLOAT, WB_SF_VEC2F, WB_SF_VEC3F, WB_SF_ROTATION,
WB_SF_COLOR, WB_SF_STRING, WB_SF_NODE, WB_MF, WB_MF_BOOL, WB_MF_INT32, WB_MF_FLOAT,
WB_MF_VEC2F, WB_MF_VEC3F, WB_MF_ROTATION, WB_MF_COLOR, WB_MF_STRING, WB_MF_NODE
} WbFieldType;
const char *wb_supervisor_field_get_name(WbFieldRef field);
WbFieldType wb_supervisor_field_get_type(WbFieldRef field);
const char *wb_supervisor_field_get_type_name(WbFieldRef field);
int wb_supervisor_field_get_count(WbFieldRef field);
WbFieldRef wb_supervisor_field_get_actual_field(WbFieldRef field);
void wb_supervisor_field_enable_sf_tracking(WbFieldRef field, int sampling_period);
void wb_supervisor_field_disable_sf_tracking(WbFieldRef field);
#include <webots/Field.hpp>
namespace webots {
class Field {
typedef enum {
SF_BOOL, SF_INT32, SF_FLOAT, SF_VEC2F, SF_VEC3F, SF_ROTATION, SF_COLOR, SF_STRING,
SF_NODE, MF, MF_BOOL, MF_INT32, MF_FLOAT, MF_VEC2F, MF_VEC3F, MF_ROTATION, MF_COLOR,
MF_STRING, MF_NODE
} Type;
std::string getName() const;
Type getType() const;
std::string getTypeName() const;
int getCount() const;
WbFieldRef getActualField() const;
void enableSFTracking(int samplingPeriod);
void disableSFTracking();
// ...
}
}
from controller import Field
class Field:
SF_BOOL, SF_INT32, SF_FLOAT, SF_VEC2F, SF_VEC3F, SF_ROTATION, SF_COLOR, SF_STRING,
SF_NODE, MF, MF_BOOL, MF_INT32, MF_FLOAT, MF_VEC2F, MF_VEC3F, MF_ROTATION, MF_COLOR,
MF_STRING, MF_NODE
def getName(self):
def getType(self):
def getTypeName(self):
def getCount(self):
def getActualField(self):
def enableSFTracking(self, samplingPeriod):
def disableSFTracking(self):
# ...
import com.cyberbotics.webots.controller.Field;
public class Field {
public final static int SF_BOOL, SF_INT32, SF_FLOAT, SF_VEC2F, SF_VEC3F, SF_ROTATION,
SF_COLOR, SF_STRING, SF_NODE, MF, MF_BOOL, MF_INT32, MF_FLOAT, MF_VEC2F, MF_VEC3F,
MF_ROTATION, MF_COLOR, MF_STRING, MF_NODE;
public String getName();
public int getType();
public String getTypeName();
public int getCount();
public Field getActualField();
public void enableSFTracking(int samplingPeriod);
public void disableSFTracking();
// ...
}
WB_SF_BOOL, WB_SF_INT32, WB_SF_FLOAT, WB_SF_VEC2F, WB_SF_VEC3F, WB_SF_ROTATION, WB_SF_COLOR,
WB_SF_STRING, WB_SF_NODE, WB_MF, WB_BOOL, WB_MF_INT32, WB_MF_FLOAT, B_MF_VEC2F, WB_MF_VEC3F,
WB_ROTATION, WB_MF_COLOR, WB_MF_STRING, WB_MF_NODE
name = wb_supervisor_field_get_name(field)
type = wb_supervisor_field_get_type(field)
name = wb_supervisor_field_get_type_name(field)
count = wb_supervisor_field_get_count(field)
actual_field = wb_supervisor_field_get_actual_field(field)
wb_supervisor_field_enable_sf_tracking(field, sampling_period)
wb_supervisor_field_disable_sf_tracking(field)
Description
get a handler and more information on a field in a node
The wb_supervisor_field_get_name
function returns the name of the field passed as an argument to this function.
If the argument is NULL, the function returns the empty string.
The wb_supervisor_field_get_type
function returns the data type of a field found previously from the wb_supervisor_node_get_field
function, as a symbolic value.
If the argument is NULL, the function returns 0.
Field types are defined in "webots/supervisor.h" and include for example: WB_SF_FLOAT
, WB_MF_NODE
, WB_SF_STRING
, etc.
The WB_MF
value doesn't represent a type but it is a bit mask value that can be used to check if the type represents a single field (SF) or a multiple field (MF).
The wb_supervisor_field_get_type_name
function returns a text string corresponding to the data type of a field found previously from the wb_supervisor_node_get_field
function.
Field type names are defined in the VRML97 specifications and include for example: "SFFloat"
, "MFNode"
, "SFString"
, etc.
If the argument is NULL, the function returns the empty string.
The wb_supervisor_field_get_count
function returns the number of items of a multiple field (MF) passed as an argument to this function.
If a single field (SF) or NULL is passed as an argument to this function, it returns -1.
Hence, this function can also be used to test if a field is MF (like WB_MF_INT32
) or SF (like WB_SF_BOOL
).
The wb_supervisor_field_get_actual_field
function returns the field in the scene tree that is associated with the given field.
This allows you to retrieve a modifiable field reference from an internal field reference. (e.g., a field reference returned by wb_supervisor_node_get_base_node_field
or wb_supervisor_proto_get_field
).
If the argument is invalid or doesn't have an associated field in the tree, the function returns NULL.
If the function does not return NULL, the returned field is guaranteed to be modifiable.
The wb_supervisor_field_enable_sf_tracking
function forces Webots to stream field data to the controller.
It improves the performance as the controller by default uses a request-response pattern to get data from the field.
The sampling_period
argument determines how often the field data should be sent to the controller.
The function is limited only to single fields.
The wb_supervisor_field_disable_sf_tracking
function disables field data tracking.
The function is limited only to single fields.
Note [C++, Java, Python]: In the oriented-object APIs, the SF_* and MF_* constants are available as static integers of the
Field
class (for example, Field::SF_BOOL). These integers can be directly compared with the output of theField::getType
function.
wb_supervisor_field_get_sf_bool
wb_supervisor_field_get_sf_int32
wb_supervisor_field_get_sf_float
wb_supervisor_field_get_sf_vec2f
wb_supervisor_field_get_sf_vec3f
wb_supervisor_field_get_sf_rotation
wb_supervisor_field_get_sf_color
wb_supervisor_field_get_sf_string
wb_supervisor_field_get_sf_node
wb_supervisor_field_get_mf_bool
wb_supervisor_field_get_mf_int32
wb_supervisor_field_get_mf_float
wb_supervisor_field_get_mf_vec2f
wb_supervisor_field_get_mf_vec3f
wb_supervisor_field_get_mf_rotation
wb_supervisor_field_get_mf_color
wb_supervisor_field_get_mf_string
wb_supervisor_field_get_mf_node
#include <webots/supervisor.h>
bool wb_supervisor_field_get_sf_bool(WbFieldRef field);
int wb_supervisor_field_get_sf_int32(WbFieldRef field);
double wb_supervisor_field_get_sf_float(WbFieldRef field);
const double *wb_supervisor_field_get_sf_vec2f(WbFieldRef sf_field);
const double *wb_supervisor_field_get_sf_vec3f(WbFieldRef field);
const double *wb_supervisor_field_get_sf_rotation(WbFieldRef field);
const double *wb_supervisor_field_get_sf_color(WbFieldRef field);
const char *wb_supervisor_field_get_sf_string(WbFieldRef field);
WbNodeRef wb_supervisor_field_get_sf_node(WbFieldRef field);
bool wb_supervisor_field_get_mf_bool(WbFieldRef field, int index);
int wb_supervisor_field_get_mf_int32(WbFieldRef field, int index);
double wb_supervisor_field_get_mf_float(WbFieldRef field, int index);
const double *wb_supervisor_field_get_mf_vec2f(WbFieldRef field, int index);
const double *wb_supervisor_field_get_mf_vec3f(WbFieldRef field, int index);
const double *wb_supervisor_field_get_mf_rotation(WbFieldRef field, int index);
const double *wb_supervisor_field_get_mf_color(WbFieldRef field, int index);
const char *wb_supervisor_field_get_mf_string(WbFieldRef field, int index);
WbNodeRef wb_supervisor_field_get_mf_node(WbFieldRef field, int index);
#include <webots/Field.hpp>
namespace webots {
class Field {
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;
bool getMFBool(int index) 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 *getMFRotation(int index) const;
const double *getMFColor(int index) const;
std::string getMFString(int index) const;
Node *getMFNode(int index) const;
// ...
}
}
from controller import Field
class Field:
def getSFBool(self):
def getSFInt32(self):
def getSFFloat(self):
def getSFVec2f(self):
def getSFVec3f(self):
def getSFRotation(self):
def getSFColor(self):
def getSFString(self):
def getSFNode(self):
def getMFBool(self, index):
def getMFInt32(self, index):
def getMFFloat(self, index):
def getMFVec2f(self, index):
def getMFVec3f(self, index):
def getMFRotation(self, index):
def getMFColor(self, index):
def getMFString(self, index):
def getMFNode(self, index):
# ...
import com.cyberbotics.webots.controller.Field;
public class Field {
public boolean getSFBool();
public int getSFInt32();
public double getSFFloat();
public double[] getSFVec2f();
public double[] getSFVec3f();
public double[] getSFRotation();
public double[] getSFColor();
public String getSFString();
public Node getSFNode();
public boolean getMFBool(int index);
public int getMFInt32(int index);
public double getMFFloat(int index);
public double[] getMFVec2f(int index);
public double[] getMFVec3f(int index);
public double[] getMFColor(int index);
public double[] getMFRotation(int index);
public String getMFString(int index);
public Node getMFNode(int index);
// ...
}
b = wb_supervisor_field_get_sf_bool(field)
i = wb_supervisor_field_get_sf_int32(field)
f = wb_supervisor_field_get_sf_float(field)
x_y_array = wb_supervisor_field_get_sf_vec2f(field)
x_y_z_array = wb_supervisor_field_get_sf_vec3f(field)
x_y_z_alpha_array = wb_supervisor_field_get_sf_rotation(field)
r_g_b_array = wb_supervisor_field_get_sf_color(field)
s = wb_supervisor_field_get_sf_string(field)
node = wb_supervisor_field_get_sf_node(field)
b = wb_supervisor_field_get_mf_bool(field, index)
i = wb_supervisor_field_get_mf_int32(field, index)
f = wb_supervisor_field_get_mf_float(field, index)
x_y_array = wb_supervisor_field_get_mf_vec2f(field, index)
x_y_z_array = wb_supervisor_field_get_mf_vec3f(field, index)
x_y_z_a_array = wb_supervisor_field_get_mf_rotation(field, index)
r_g_b_array = wb_supervisor_field_get_mf_color(field, index)
s = wb_supervisor_field_get_mf_string(field, index)
node = wb_supervisor_field_get_mf_node(field, index)
Description
get the value of a field
The wb_supervisor_field_get_sf_*
functions retrieve the value of a specified single field
(SF).
The type of the field has to match the name of the function used, otherwise the return value is undefined (and a warning message is displayed).
If the field
parameter is NULL, it has the wrong type, or the index
is not valid, then a default value is returned.
Default values are defined as 0
and 0.0
for integer and double values, false
in case of boolean values, NULL for vectors and pointers and the empty string ""
for strings.
The wb_supervisor_field_get_mf_*
functions work the same way as the wb_supervisor_field_get_sf_*
functions but with multiple field
argument.
They take an additional index
argument which refers to the index of the item in the multiple field (MF).
The type of the field has to match with the name of the function. The index should be comprised between minus the total number of items and the total number of items minus one. Using a negative index starts the count from the last element of the field until the first one. Index -1 represents the last item and the first item is represented by index 0 (or minus number of items).
Note: If a
wb_supervisor_field_set_*
function is executed just before a correspondingwb_supervisor_field_get_*
function, in the same time step, the controller library will not send the query to Webots, but answer directly with the value that has just been set before.
wb_supervisor_field_set_sf_bool
wb_supervisor_field_set_sf_int32
wb_supervisor_field_set_sf_float
wb_supervisor_field_set_sf_vec2f
wb_supervisor_field_set_sf_vec3f
wb_supervisor_field_set_sf_rotation
wb_supervisor_field_set_sf_color
wb_supervisor_field_set_sf_string
wb_supervisor_field_set_mf_bool
wb_supervisor_field_set_mf_int32
wb_supervisor_field_set_mf_float
wb_supervisor_field_set_mf_vec2f
wb_supervisor_field_set_mf_vec3f
wb_supervisor_field_set_mf_rotation
wb_supervisor_field_set_mf_color
wb_supervisor_field_set_mf_string
#include <webots/supervisor.h>
void wb_supervisor_field_set_sf_bool(WbFieldRef field, bool value);
void wb_supervisor_field_set_sf_int32(WbFieldRef field, int value);
void wb_supervisor_field_set_sf_float(WbFieldRef field, double value);
void wb_supervisor_field_set_sf_vec2f(WbFieldRef sf_field, const double values[2]);
void wb_supervisor_field_set_sf_vec3f(WbFieldRef field, const double values[3]);
void wb_supervisor_field_set_sf_rotation(WbFieldRef field, const double values[4]);
void wb_supervisor_field_set_sf_color(WbFieldRef field, const double values[3]);
void wb_supervisor_field_set_sf_string(WbFieldRef field, const char *value);
void wb_supervisor_field_set_mf_bool(WbFieldRef field, int index, bool value);
void wb_supervisor_field_set_mf_int32(WbFieldRef field, int index, int value);
void wb_supervisor_field_set_mf_float(WbFieldRef field, int index, double value);
void wb_supervisor_field_set_mf_vec2f(WbFieldRef field, int index, const double values[2]);
void wb_supervisor_field_set_mf_vec3f(WbFieldRef field, int index, const double values[3]);
void wb_supervisor_field_set_mf_rotation(WbFieldRef field, int index, const double values[4]);
void wb_supervisor_field_set_mf_color(WbFieldRef field, int index, const double values[3]);
void wb_supervisor_field_set_mf_string(WbFieldRef field, int index, const char *value);
#include <webots/Field.hpp>
namespace webots {
class Field {
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 setMFBool(int index, bool 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 setMFRotation(int index, const double values[4]);
void setMFColor(int index, const double values[3]);
void setMFString(int index, const std::string &value);
// ...
}
}
from controller import Field
class Field:
def setSFBool(self, value):
def setSFInt32(self, value):
def setSFFloat(self, value):
def setSFVec2f(self, values):
def setSFVec3f(self, values):
def setSFRotation(self, values):
def setSFColor(self, values):
def setSFString(self, value):
def setMFBool(self, index, value):
def setMFInt32(self, index, value):
def setMFFloat(self, index, value):
def setMFVec2f(self, index, values):
def setMFVec3f(self, index, values):
def setMFRotation(self, index, values):
def setMFColor(self, index, values):
def setMFString(self, index, value):
# ...
import com.cyberbotics.webots.controller.Field;
public class Field {
public void setSFBool(boolean value);
public void setSFInt32(int value);
public void setSFFloat(double value);
public void setSFVec2f(double values[2]);
public void setSFVec3f(double values[3]);
public void setSFRotation(double values[4]);
public void setSFColor(double values[3]);
public void setSFString(String value);
public void setMFBool(int index, boolean value);
public void setMFInt32(int index, int value);
public void setMFFloat(int index, double value);
public void setMFVec2f(int index, double values[2]);
public void setMFVec3f(int index, double values[3]);
public void setMFRotation(int index, double values[4]);
public void setMFColor(int index, double values[3]);
public void setMFString(int index, String value);
// ...
}
wb_supervisor_field_set_sf_bool(field, value)
wb_supervisor_field_set_sf_int32(field, value)
wb_supervisor_field_set_sf_float(field, value)
wb_supervisor_field_set_sf_vec2f(field, [x y])
wb_supervisor_field_set_sf_vec3f(field, [x y z])
wb_supervisor_field_set_sf_rotation(field, [x y z alpha])
wb_supervisor_field_set_sf_color(field, [r g b])
wb_supervisor_field_set_sf_string(field, 'value')
wb_supervisor_field_set_mf_bool(field, index, value)
wb_supervisor_field_set_mf_int32(field, index, value)
wb_supervisor_field_set_mf_float(field, index, value)
wb_supervisor_field_set_mf_vec2f(field, index, [x y])
wb_supervisor_field_set_mf_vec3f(field, index, [x y z])
wb_supervisor_field_set_mf_rotation(field, index, [x y z a])
wb_supervisor_field_set_mf_color(field, index, [r g b])
wb_supervisor_field_set_mf_string(field, index, 'value')
Description
set the value of a field
The wb_supervisor_field_set_sf_*
functions assign a value to a specified single field
(SF).
The type of the field has to match with the name of the function used, otherwise the value of the field remains unchanged (and a warning message is displayed).
The wb_supervisor_field_set_mf_*
functions work the same way as the wb_supervisor_field_set_sf_*
functions but with a multiple field
(MF) argument.
They take an additional index
argument which refers to the index of the item in the multiple field.
The type of the field has to match with the name of the function. The index should be comprised between minus the total number of items and the total number of items minus one. Using a negative index starts the count from the last element of the field until the first one. Index -1 represents the last item and the first item is represented by index 0 (or minus number of items).
The set operations are received by Webots from possibly several supervisors running concurrently.
In order to ensure reproducible simulation results, they are executed only once all set operations are received, just before advancing the simulation time.
The order of execution of the set operations is defined by the order of the Robot nodes in the scene tree.
As a consequence, if a supervisor sets the translation field of a node and immediately retrieves the absolute position of the same node using the wb_supervisor_node_get_position
function, it will actually get the previous position of the node.
This is because the execution of the set operation is postponed to the beginning of the next simulation step.
In order to retrieve the new position of the node, a wb_robot_step
function call with a non-zero argument should be executed before calling the wb_supervisor_node_get_position
function.
An exception to this rule applies if one of the following functions is executed:
wb_supervisor_field_insert_mf_*
wb_supervisor_field_import_mf_node_from_string
wb_supervisor_field_import_sf_node_from_string
wb_supervisor_field_remove_mf
wb_supervisor_field_remove_sf
In this case, the set operations queued in the current step of this controller only are executed just before the insert, import or remove operation.
Note: Since Webots 7.4.4, the inertia of a solid is no longer automatically reset when changing its translation or rotation using
wb_supervisor_field_set_sf_vec2f
andwb_supervisor_field_set_sf_rotation
functions. If needed, the user has to explicitly call this section function.
Examples
The "texture_change.wbt" world, located in the "projects/samples/howto/texture_change/worlds" directory, shows how to change a texture from the supervisor while the simulation is running. The "soccer.wbt" world, located in the "projects/samples/demos/worlds" directory, provides a simple example for getting and setting fields with the above described functions.
wb_supervisor_field_insert_mf_bool
wb_supervisor_field_insert_mf_int32
wb_supervisor_field_insert_mf_float
wb_supervisor_field_insert_mf_vec2f
wb_supervisor_field_insert_mf_vec3f
wb_supervisor_field_insert_mf_rotation
wb_supervisor_field_insert_mf_color
wb_supervisor_field_insert_mf_string
wb_supervisor_field_remove_mf
wb_supervisor_field_remove_sf
#include <webots/supervisor.h>
void wb_supervisor_field_insert_mf_bool(WbFieldRef field, int index, bool value);
void wb_supervisor_field_insert_mf_int32(WbFieldRef field, int index, int value);
void wb_supervisor_field_insert_mf_float(WbFieldRef field, int index, double value);
void wb_supervisor_field_insert_mf_vec2f(WbFieldRef field, int index, const double values[2]);
void wb_supervisor_field_insert_mf_vec3f(WbFieldRef field, int index, const double values[3]);
void wb_supervisor_field_insert_mf_rotation(WbFieldRef field, int index, const double values[4]);
void wb_supervisor_field_insert_mf_color(WbFieldRef field, int index, const double values[3]);
void wb_supervisor_field_insert_mf_string(WbFieldRef field, int index, const char *value);
void wb_supervisor_field_remove_mf(WbFieldRef field, int index);
void wb_supervisor_field_remove_sf(WbFieldRef field);
#include <webots/Field.hpp>
namespace webots {
class Field {
void insertSFBool(bool value);
void insertSFInt32(int value);
void insertSFFloat(double value);
void insertSFVec2f(const double values[2]);
void insertSFVec3f(const double values[3]);
void insertSFRotation(const double values[4]);
void insertSFColor(const double values[3]);
void insertSFString(const std::string &value);
void insertMFBool(int index, bool value);
void insertMFInt32(int index, int value);
void insertMFFloat(int index, double value);
void insertMFVec2f(int index, const double values[2]);
void insertMFVec3f(int index, const double values[3]);
void insertMFRotation(int index, const double values[4]);
void insertMFColor(int index, const double values[3]);
void insertMFString(int index, const std::string &value);
void removeMF(int index);
void removeSF();
// ...
}
}
from controller import Field
class Field:
def insertMFBool(self, index, value):
def insertMFInt32(self, index, value):
def insertMFFloat(self, index, value):
def insertMFVec2f(self, index, values):
def insertMFVec3f(self, index, values):
def insertMFRotation(self, index, values):
def insertMFColor(self, index, values):
def insertMFString(self, index, value):
def removeMF(self, index):
def removeSF(self):
# ...
import com.cyberbotics.webots.controller.Field;
public class Field {
public void insertMFBool(int index, boolean value);
public void insertMFInt32(int index, int value);
public void insertMFFloat(int index, double value);
public void insertMFVec2f(int index, double values[2]);
public void insertMFVec3f(int index, double values[3]);
public void insertMFRotation(int index, double values[4]);
public void insertMFColor(int index, double values[3]);
public void insertMFString(int index, String value);
public void removeMF(int index);
public void removeSF();
// ...
}
wb_supervisor_field_insert_mf_bool(field, index, value)
wb_supervisor_field_insert_mf_int32(field, index, value)
wb_supervisor_field_insert_mf_float(field, index, value)
wb_supervisor_field_insert_mf_vec2f(field, index, [x y])
wb_supervisor_field_insert_mf_vec3f(field, index, [x y z])
wb_supervisor_field_insert_mf_rotation(field, index, [x y z a])
wb_supervisor_field_insert_mf_color(field, index, [r g b])
wb_supervisor_field_insert_mf_string(field, index, 'value')
wb_supervisor_field_remove_mf(field, index)
wb_supervisor_field_remove_sf(field)
Description
insert or remove a value in a field
The wb_supervisor_field_insert_mf_*
functions insert an item to a specified multiple field
(MF).
The type of the field has to match with the name of the function used, otherwise the field remains unchanged (and a warning message is displayed).
The index
parameter defines the position in the MF field where the new item will be inserted.
It can be positive or negative.
Here are a few examples for the index
parameter:
- 0: insert at the beginning of the field.
- 1: insert at the second index.
- 2: insert at the third index.
- -1: insert at the last index.
- -2: insert at the second index from the end of the field.
- -3: insert at the third index from the end.
The wb_supervisor_field_remove_sf/mf
functions remove an item from a specified field
(MF or SF).
If the item is the Robot node itself, it is removed only at the end of the step.
wb_supervisor_field_import_mf_node_from_string
wb_supervisor_field_import_sf_node_from_string
#include <webots/supervisor.h>
void wb_supervisor_field_import_mf_node_from_string(WbFieldRef field, int position, const char *node_string);
void wb_supervisor_field_import_sf_node_from_string(WbFieldRef field, const char *node_string);
#include <webots/Field.hpp>
namespace webots {
class Field {
void importMFNodeFromString(int position, const std::string &nodeString);
void importSFNodeFromString(const std::string &nodeString);
// ...
}
}
from controller import Field
class Field:
def importMFNodeFromString(self, position, nodeString):
def importSFNodeFromString(self, nodeString):
# ...
import com.cyberbotics.webots.controller.Field;
public class Field {
public void importMFNodeFromString(int position, String nodeString);
public void importSFNodeFromString(String nodeString);
// ...
}
wb_supervisor_field_import_mf_node_from_string(field, position, 'node_string')
wb_supervisor_field_import_sf_node_from_string(field, 'node_string')
Description
import a node into an MF_NODE or SF_NODE field (typically a "children" field)
The wb_supervisor_field_import_mf_node_from_string
and wb_supervisor_field_import_sf_node_from_string
functions import a Webots node into an MF_NODE
or SF_NODE
field.
This node should be defined in the node_string
parameter.
Note: only PROTO that have been previously declared as
IMPORTABLE EXTERNPROTO
can be spawned using the supervisor. This can be done by pressing the similarly named button above the scene tree. More information is available here.
The position
parameter defines the position in the MF_NODE
where the new node will be inserted.
It can be positive or negative.
Here are a few examples for the position
parameter:
- 0: insert at the beginning of the scene tree.
- 1: insert at the second position.
- 2: insert at the third position.
- -1: insert at the last position.
- -2: insert at the second position from the end of the scene tree.
- -3: insert at the third position from the end.
This function is typically used in order to add a node into a "children" field. Note that a node can be imported into the scene tree by calling this function with the "children" field of the root node.
For example, if you want to create a new robot with a specific controller:
#include <webots/robot.h>
#include <webots/supervisor.h>
#define TIME_STEP 32
int main(int argc, char **argv) {
wb_robot_init();
WbNodeRef root_node = wb_supervisor_node_get_root();
WbFieldRef root_children_field = wb_supervisor_node_get_field(root_node, "children");
wb_supervisor_field_import_mf_node_from_string(root_children_field, 4, "DEF MY_ROBOT Robot { controller \"my_controller\" }");
...
}
from controller import Supervisor
supervisor = Supervisor()
rootNode = supervisor.getRoot() # get root of the scene tree
rootChildrenField = rootNode.getField('children')
rootChildrenField.importMFNodeFromString(4, 'DEF MY_ROBOT Robot { controller "my_controller" }')
...
Note: To remove a node use the
wb_supervisor_field_remove_mf
function.
wb_supervisor_proto_get_type_name
wb_supervisor_proto_is_derived
wb_supervisor_proto_get_parent
#include <webots/supervisor.h>
const char *wb_supervisor_proto_get_type_name(WbProtoRef proto);
bool wb_supervisor_proto_is_derived(WbProtoRef proto, const char *type_name);
WbProtoRef wb_supervisor_proto_get_parent(WbProtoRef proto);
#include <webots/Proto.hpp>
namespace webots {
class Proto {
std::string getTypeName();
bool isDerived();
Node getParent();
// ...
}
}
from controller import Proto
class Proto:
def getTypeName(self):
def isDerived(self):
def getParent(self):
# ...
import com.cyberbotics.webots.controller.Proto;
public class Proto {
public String getTypeName();
public boolean isDerived();
public Node getParent();
// ...
}
type_name = wb_supervisor_proto_get_type_name(proto)
is_derived = wb_supervisor_proto_is_derived(proto)
parent = wb_supervisor_proto_get_parent(proto)
Description
get information about a proto instance
The wb_supervisor_proto_get_type
function returns the type name of a proto instance as defined in the PROTO file.
If the argument is NULL, the function returns the empty string.
The wb_supervisor_proto_is_derived
function returns true if the proto instance is derived from another proto type.
The wb_supervisor_proto_get_parent
function returns the instance of the parent proto type corresponding to the given proto instance.
wb_supervisor_proto_get_field
wb_supervisor_proto_get_field_by_index
wb_supervisor_proto_get_number_of_fields
#include <webots/supervisor.h>
WbFieldRef wb_supervisor_proto_get_field(WbProtoRef proto, const char *field_name);
WbFieldRef wb_supervisor_proto_get_field_by_index(WbProtoRef proto, int index);
int wb_supervisor_proto_get_number_of_fields(WbProtoRef proto);
#include <webots/Proto.hpp>
namespace webots {
class Proto {
Field getField(const std::string &fieldName);
Field getFieldByIndex(int index);
int getNumberOfFields();
// ...
}
}
from controller import Proto
class Proto:
def getField(self, fieldName):
def getFieldByIndex(self, index):
def getNumberOfFields(self):
# ...
import com.cyberbotics.webots.controller.Proto;
public class Proto {
public Field getField(String fieldName);
public Field getFieldByIndex(int index);
public int getNumberOfFields();
// ...
}
field = wb_supervisor_proto_get_field(proto, 'field_name')
field = wb_supervisor_proto_get_field_by_index(proto, index)
number_of_fields = wb_supervisor_proto_get_number_of_fields(proto)
Description
get information about a proto instance's fields
The wb_supervisor_proto_get_field
function returns the field of a proto instance corresponding to the given field name.
If the field does not exist or the provided proto is invalid, the function returns NULL.
The wb_supervisor_proto_get_field_by_index
function returns the field of a proto instance corresponding to the given index.
If the field does not exist or the provided proto is invalid, the function returns NULL.
The wb_supervisor_proto_get_number_of_fields
function returns the number of fields of a proto instance.
If the provided proto is invalid, the function returns -1.
wb_supervisor_virtual_reality_headset_is_used
wb_supervisor_virtual_reality_headset_get_position
wb_supervisor_virtual_reality_headset_get_orientation
#include <webots/supervisor.h>
bool wb_supervisor_virtual_reality_headset_is_used();
const double *wb_supervisor_virtual_reality_headset_get_position();
const double *wb_supervisor_virtual_reality_headset_get_orientation();
#include <webots/Supervisor.hpp>
namespace webots {
class Supervisor : public Robot {
bool virtualRealityHeadsetIsUsed();
const double *virtualRealityHeadsetGetPosition();
const double *virtualRealityHeadsetGetOrientation();
// ...
}
}
from controller import Supervisor
class Supervisor (Robot):
def virtualRealityHeadsetIsUsed(self):
def virtualRealityHeadsetGetPosition(self):
def virtualRealityHeadsetGetOrientation(self):
# ...
import com.cyberbotics.webots.controller.Supervisor;
public class Supervisor extends Robot {
public boolean virtualRealityHeadsetIsUsed();
public double[] virtualRealityHeadsetGetPosition();
public double[] virtualRealityHeadsetGetOrientation();
// ...
}
used = wb_supervisor_virtual_reality_headset_is_used()
position = wb_supervisor_virtual_reality_headset_get_position()
orientation = wb_supervisor_virtual_reality_headset_get_orientation()
Description
check if a virtual reality headset is used and get its position and orientation
The wb_supervisor_virtual_reality_headset_is_used
function returns true if a virtual reality headset is currently used to view the simulation.
For more information about how to use a virtual reality headset refer to the User Guide.
The wb_supervisor_virtual_reality_headset_get_position
and wb_supervisor_virtual_reality_headset_get_orientation
functions return respectively the current position and orientation of the virtual reality headset as a vector of 3 doubles and a matrix containing 9 doubles that should be interpreted as a 3 x 3 orthogonal rotation matrix:
[ R[0] R[1] R[2] ]
[ R[3] R[4] R[5] ]
[ R[6] R[7] R[8] ]
If the position or the orientation of the virtual reality headset is not tracked or no virtual reality headset is currently used, these functions will return NaN
(Not a Number) values.
Contact Point
A contact point object is defined by the following structure:
#include <webots/contact_point.h>
typedef struct {
double point[3];
int node_id;
} WbContactPoint;
#include <webots/Node.hpp>
namespace webots {
typedef struct {
double point[3];
int node_id;
} ContactPoint;
}
from controller import ContactPoint
ContactPoint:
def __init__(self):
self.point -> list[float]
self.node_id -> int
def getPoint(self):
def getNodeId(self):
import com.cyberbotics.webots.controller.ContactPoint;
public class ContactPoint {
public double[] getPoint();
public int getNodeId();
}
structs.WbContactPoint.members = struct(
'point', 'double#3',
'node_id', 'int32',
);
Description
The point
represents a position of a contact point expressed in the global (world) coordinate system.
The node_id
represents an ID of the node associated to a contact point.