|
| | RigidBodyDepthSensor (RigidBodySystem const &sys, const std::string &name, const std::shared_ptr< RigidBodyFrame > frame, tinyxml2::XMLElement *node) |
| |
| | RigidBodyDepthSensor (RigidBodySystem const &sys, const std::string &name, const std::shared_ptr< RigidBodyFrame > frame, std::size_t samples, double min_angle, double max_angle, double range) |
| |
| | ~RigidBodyDepthSensor () override |
| |
| size_t | getNumOutputs () const override |
| |
| virtual bool | is_horizontal_scanner () const |
| | Returns true if this sensor scans horizontally. More...
|
| |
| virtual bool | is_vertical_scanner () const |
| | Returns true if this sensor scans vertically. More...
|
| |
| virtual size_t | num_pixel_rows () const |
| | Returns the number of points in the image vertically (pitch). More...
|
| |
| virtual size_t | num_pixel_cols () const |
| | Returns the number of points in the image horizontally (yaw). More...
|
| |
| virtual double | min_pitch () const |
| | Returns minimum pitch of this sensor's FOV in radians. More...
|
| |
| virtual double | max_pitch () const |
| | Returns maximum pitch of this sensor's FOV in radians. More...
|
| |
| virtual double | min_yaw () const |
| | Returns the minimum yaw of this sensor's FOV in radians. More...
|
| |
| virtual double | max_yaw () const |
| | Returns the maximum yaw of this sensor's FOV in radians. More...
|
| |
| virtual double | min_range () const |
| | Returns the minimum range of this sensor in meters. More...
|
| |
| virtual double | max_range () const |
| | Returns the maximum range of this sensor in meters. More...
|
| |
| Eigen::VectorXd | output (const double &t, const KinematicsCache< double > &rigid_body_state, const RigidBodySystem::InputVector< double > &u) const override |
| |
Public Member Functions inherited from RigidBodySensor |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | RigidBodySensor (const RigidBodySystem &sys, const std::string &name, std::shared_ptr< RigidBodyFrame > frame) |
| | The constructor. More...
|
| |
| virtual | ~RigidBodySensor () |
| |
| virtual bool | isDirectFeedthrough () const |
| |
| const std::string & | get_name () const |
| | Returns the name of the sensor. More...
|
| |
| const std::string & | get_model_name () const |
| | Returns the name of the model (i.e., robot) that owns this sensor. More...
|
| |
| const RigidBodyFrame & | get_frame () const |
| | Returns the frame to which thi sensor is attached. More...
|
| |
| const RigidBodySystem & | get_rigid_body_system () const |
| | Returns the rigid body system to which this sensor attaches. More...
|
| |
RigidBodyDepthSensor.
Uses raycast to simulate a depth image at some evenly spaced pixel rows and columns.