Sensors

This module provides a way to specify sensor properties using a URDF-like format. We provide a few implementation examples for depth camera, RGB camera, and IMU.

We use RaiSim to interface with the real hardware. This makes sense because we want to use the same code to control both the simulated and real robot. This sensor package is also designed for real robots as well. This might confuse some people but it makes the code simpler and shorter.

Update

The sensor update method can be set using raisim::Sensor::setMeasurementSource. It can be either updated using raisim (raisim::Sensor::MeasurementSource::RAISIM) or the visualizer (raisim::Sensor::MeasurementSource::VISUALIZER). RGBSensor can only be updated using the RaisimUnreal. DepthSensor can be updated either raisim or the RaisimUnreal. InertialMeasurementUnit can only be updated using raisim.

The update is performed at the specified frequency (i.e., update_rate in the sensor xml).

Parent Class API

class Sensor

Subclassed by raisim::DepthCamera, raisim::InertialMeasurementUnit, raisim::RGBCamera

Public Functions

inline const Vec<3> &getPosition()

The pose is updated using updatePose() method. updatePose() can be called by the user. If the visualizer updates the measurement, the server will call this method before the measurement update.

Returns

The position of the sensor frame

inline const Mat<3, 3> &getOrientation()

The pose is updated using updatePose() method. updatePose() can be called by the user. If the visualizer updates the measurement, the server will call this method before the measurement update.

Returns

The orientation of the sensor frame

inline const Vec<3> &getFramePosition()
Returns

The position of the frame w.r.t. the nearest moving parent. It is used to compute the frame position in the world frame

inline const Mat<3, 3> &getFrameOrientation()
Returns

The orientation of the frame w.r.t. the nearest moving parent. It is used to compute the frame position in the world frame

inline const Vec<3> &getPosInSensorFrame()
Returns

The position of the frame w.r.t. the sensor frame, which is the frame of the parent joint

inline const Mat<3, 3> &getOriInSensorFrame()
Returns

The orientation of the frame w.r.t. the sensor frame, which is the frame of the parent joint

inline const std::string &getName()
Returns

The name of the sensor

inline Type getType()
Returns

The type of the sensor

inline double getUpdateRate() const
Returns

The update frequency in Hz

inline double getUpdateTimeStamp() const

This method will return negative value if it has never been updated

Returns

The time when the last sensor measurement was recorded

inline void setUpdateRate(double rate)

change the update rate of the sensor. The rate is given in Hz

Parameters

rate[in] the update rate in Hz

inline void setUpdateTimeStamp(double time)

Set the time stamp for the last sensor measurement

Parameters

time[in] the time stamp

virtual char *serializeProp(char *data) const = 0

Used by the server. Do not use it if you don’t know what it does. It serialized the camera property

Parameters

data[in] the pointer where the property is written

Returns

the pointer where the next data should be written

inline virtual char *serializeMeasurements(char *data) const

Used by the server. Do not use it if you don’t know what it does. It serialized the camera property

Parameters

data[in] the pointer where the property is written

Returns

the pointer where the next data should be written

void updatePose()

update the pose of the sensor from the articulated system

inline MeasurementSource getMeasurementSource()
Returns

The measurement source.

inline void setMeasurementSource(MeasurementSource source)

change the measurement source

Parameters

source[in] The measurement source.

inline size_t getFrameId() const

Get the id of the frame on which the sensor is attached

Returns

frame id

inline void lockMutex()

locks sensor mutex. This can be used if you use raisim in a multi-threaded environment.

inline void unlockMutex()

unlock sensor mutex. This can be used if you use raisim in a multi-threaded environment.

Depth Camera API

class DepthCamera : public raisim::Sensor

Public Functions

inline virtual char *serializeProp(char *data) const final

Used by the server. Do not use it if you don’t know what it does. It serialized the camera property

Parameters

data[in] the pointer where the property is written

Returns

the pointer where the next data should be written

inline void set3DPoints(const std::vector<raisim::Vec<3>> &data)

This method is only useful on the real robot (and you use raisim on the real robot). You can set the 3d point array manually

Parameters

data[in] The 3d point data

inline const std::vector<float> &getDepthArray() const

This method will return garbage if it has never been updated. Makes sure that the updateTimeStep is positive (negative means that it has never been updated)

Returns

depthArray

inline void setDepthArray(const std::vector<float> &depthIn)

Set the data manually. This can be useful on the real robot

Parameters

depthIn[in] Depth values

Returns

The image data in char vector

inline const std::vector<raisim::Vec<3>, AlignedAllocator<raisim::Vec<3>, 32>> &get3DPoints() const

This method works only if the measurement source is Raisim

Returns

3D points in the world frame

inline const DepthCameraProperties &getProperties() const

Get the depth camera properties

Returns

the depth camera properties

virtual void update(class World &world) final

Update the sensor value

Parameters

world[in] the world that the sensor is in

void depthToPointCloud(const std::vector<float> &depthArray, std::vector<raisim::Vec<3>> &pointCloud, bool isInSensorFrame = false) const

Convert the depth values to 3D coordinates

Parameters
  • depthArray[in] input depth array to convert

  • pointCloud[out] output point cloud

  • sensorFrame[in] If the 3D points are expressed in the sensor frame or the world frame

struct DepthCameraProperties

Public Types

enum class NoiseType : int

noise type - CURRENTLY NOT USED

Values:

enumerator GAUSSIAN
enumerator UNIFORM
enumerator NO_NOISE

RGB Camera API

class RGBCamera : public raisim::Sensor

Public Functions

inline virtual char *serializeProp(char *data) const final

Used by the server. Do not use it if you don’t know what it does. It serialized the camera property

Parameters

data[in] the pointer where the property is written

Returns

the pointer where the next data should be written

inline const RGBCameraProperties &getProperties() const

Return the camera properties

Returns

camera properties

inline const std::vector<char> &getImageBuffer() const

rgb image in bgra format. It is updated only if the measurement source is the visualizer and raisimUnreal is used

Returns

The image data in char vector

inline void setImageBuffer(const std::vector<char> &rgbaIn)

Set RGBA data. This method is only useful on the real robot.

Parameters

rgbaIn[in] rgba

struct RGBCameraProperties

Inertial Measurement Unit API

class InertialMeasurementUnit : public raisim::Sensor

Public Functions

inline virtual char *serializeProp(char *data) const final

Used by the server. Do not use it if you don’t know what it does. It serialized the camera property

Parameters

data[in] the pointer where the property is written

Returns

the pointer where the next data should be written

inline virtual char *serializeMeasurements(char *data) const

Used by the server. Do not use it if you don’t know what it does. It serialized the camera property

Parameters

data[in] the pointer where the property is written

Returns

the pointer where the next data should be written

inline const Eigen::Vector3d &getLinearAcceleration() const

Get the linear acceleration measured by the sensor. In simulation, this is updated every update loop (set by the updateRate). On the real robot, this value should be set externally by setLinearAcceleration()

Returns

linear acceleration

inline const Eigen::Vector3d &getAngularVelocity() const

Get the angular velocity measured by the sensor. In simulation, this is updated every update loop (set by the updateRate). On the real robot, this value should be set externally by setAngularVelocity()

Returns

angular velocity

inline const Vec<4> &getOrientation() const

Get the angular velocity measured by the sensor. In simulation, this is updated every update loop (set by the updateRate). On the real robot, this value should be set externally by setAngularVelocity()

Returns

angular velocity

inline void setLinearAcceleration(const Eigen::Vector3d &acc)

This set method make sense only on the real robot.

Parameters

acc – acceleration measured from sensor

inline void setAngularVelocity(const Eigen::Vector3d &vel)

This set method make sense only on the real robot.

Parameters

vel – angular velocity measured from sensor

inline void setOrientation(const Vec<4> &orientation)

This set method make sense only on the real robot.

Parameters

orientation – orientation of the imu sensor in quaternion (w,x,y,z convention)

inline virtual void update(class World &world) final

The update is done by ArticulatedSystem class and this method is not necessary

struct ImuProperties

Public Types

enum class NoiseType : int

noise type

Values:

enumerator GAUSSIAN
enumerator UNIFORM
enumerator NO_NOISE