perception_interfaces 1.0.0
|
Getter functions for objects state members. More...
Go to the source code of this file.
Functions | |
double | perception_msgs::object_access::getX (const ObjectState &state) |
Get the x-position for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getX (const T &obj) |
Get the x-position for a given template object that contains an object state. | |
double | perception_msgs::object_access::getY (const ObjectState &state) |
Get the y-position for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getY (const T &obj) |
Get the y-position for a given template object that contains an object state. | |
double | perception_msgs::object_access::getZ (const ObjectState &state) |
Get the z-position for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getZ (const T &obj) |
Get the z-position for a given template object that contains an object state. | |
double | perception_msgs::object_access::getVelLon (const ObjectState &state) |
Get the longitudinal velocity for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getVelLon (const T &obj) |
Get the longitudinal velocity for a given template object that contains an object state. | |
double | perception_msgs::object_access::getVelLat (const ObjectState &state) |
Get the longitudinal velocity for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getVelLat (const T &obj) |
Get the longitudinal velocity for a given template object that contains an object state. | |
double | perception_msgs::object_access::getAccLon (const ObjectState &state) |
Get the longitudinal acceleration for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getAccLon (const T &obj) |
Get the longitudinal acceleration for a given template object that contains an object state. | |
double | perception_msgs::object_access::getAccLat (const ObjectState &state) |
Get the lateral acceleration for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getAccLat (const T &obj) |
Get the lateral acceleration for a given template object that contains an object state. | |
double | perception_msgs::object_access::getRoll (const ObjectState &state) |
Get the roll for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getRoll (const T &obj) |
Get the roll for a given template object that contains an object state. | |
double | perception_msgs::object_access::getRollRate (const ObjectState &state) |
Get the roll-rate for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getRollRate (const T &obj) |
Get the roll-rate for a given template object that contains an object state. | |
double | perception_msgs::object_access::getPitch (const ObjectState &state) |
Get the pitch for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getPitch (const T &obj) |
Get the pitch for a given template object that contains an object state. | |
double | perception_msgs::object_access::getPitchRate (const ObjectState &state) |
Get the pitch-rate for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getPitchRate (const T &obj) |
Get the pitch-rate for a given template object that contains an object state. | |
double | perception_msgs::object_access::getYaw (const ObjectState &state) |
Get the yaw for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getYaw (const T &obj) |
Get the yaw for a given template object that contains an object state. | |
double | perception_msgs::object_access::getYawRate (const ObjectState &state) |
Get the yaw-rate for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getYawRate (const T &obj) |
Get the yaw-rate for a given template object that contains an object state. | |
double | perception_msgs::object_access::getSteeringAngleAck (const ObjectState &state) |
Get the ackermann steering angle for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getSteeringAngleAck (const T &obj) |
Get the ackermann steering angle for a given template object that contains an object state. | |
double | perception_msgs::object_access::getSteeringAngleRateAck (const ObjectState &state) |
Get the steering angle rate for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getSteeringAngleRateAck (const T &obj) |
Get the steering angle rate for a given template object that contains an object state. | |
double | perception_msgs::object_access::getSteeringAngleFront (const ObjectState &state) |
Get the front wheel angle for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getSteeringAngleFront (const T &obj) |
Get the front wheel angle for a given template object that contains an object state. | |
double | perception_msgs::object_access::getSteeringAngleRear (const ObjectState &state) |
Get the rear wheel angle for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getSteeringAngleRear (const T &obj) |
Get the rear wheel angle for a given template object that contains an object state. | |
double | perception_msgs::object_access::getWidth (const ObjectState &state) |
Get the width for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getWidth (const T &obj) |
Get the width for a given template object that contains an object state. | |
double | perception_msgs::object_access::getLength (const ObjectState &state) |
Get the length for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getLength (const T &obj) |
Get the length for a given template object that contains an object state. | |
double | perception_msgs::object_access::getHeight (const ObjectState &state) |
Get the height for a given object state. | |
template<typename T > | |
double | perception_msgs::object_access::getHeight (const T &obj) |
Get the height for a given template object that contains an object state. | |
bool | perception_msgs::object_access::getStandstill (const ObjectState &state) |
Get standstill indication for a given object state. | |
template<typename T > | |
bool | perception_msgs::object_access::getStandstill (const T &obj) |
Get the standstill indication for a given template object that contains an object state. | |
uint8_t | perception_msgs::object_access::getTrafficLightState (const ObjectState &state) |
Get the traffic light state for a given object state. | |
template<typename T > | |
uint8_t | perception_msgs::object_access::getTrafficLightState (const T &obj) |
Get the traffic light state for a given template object that contains an object state. | |
uint8_t | perception_msgs::object_access::getTrafficLightType (const ObjectState &state) |
Get the traffic light type for a given object state. | |
template<typename T > | |
uint8_t | perception_msgs::object_access::getTrafficLightType (const T &obj) |
Get the traffic light type for a given template object that contains an object state. | |
Getter functions for objects state members.
============================================================================ MIT License
Copyright (c) 2025 Institute for Automotive Engineering (ika), RWTH Aachen University
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
Definition in file state_getters.h.
|
inline |
Get the lateral acceleration for a given object state.
state |
Definition at line 184 of file state_getters.h.
|
inline |
Get the lateral acceleration for a given template object that contains an object state.
T |
obj |
Definition at line 197 of file state_getters.h.
|
inline |
Get the longitudinal acceleration for a given object state.
state |
Definition at line 161 of file state_getters.h.
|
inline |
Get the longitudinal acceleration for a given template object that contains an object state.
T |
obj |
Definition at line 174 of file state_getters.h.
|
inline |
Get the height for a given object state.
state |
Definition at line 483 of file state_getters.h.
|
inline |
Get the height for a given template object that contains an object state.
T |
obj |
Definition at line 496 of file state_getters.h.
|
inline |
Get the length for a given object state.
state |
Definition at line 460 of file state_getters.h.
|
inline |
Get the length for a given template object that contains an object state.
T |
obj |
Definition at line 473 of file state_getters.h.
|
inline |
Get the pitch for a given object state.
state |
Definition at line 253 of file state_getters.h.
|
inline |
Get the pitch for a given template object that contains an object state.
T |
obj |
Definition at line 266 of file state_getters.h.
|
inline |
Get the pitch-rate for a given object state.
state |
Definition at line 276 of file state_getters.h.
|
inline |
Get the pitch-rate for a given template object that contains an object state.
T |
obj |
Definition at line 289 of file state_getters.h.
|
inline |
Get the roll for a given object state.
state |
Definition at line 207 of file state_getters.h.
|
inline |
Get the roll for a given template object that contains an object state.
T |
obj |
Definition at line 220 of file state_getters.h.
|
inline |
Get the roll-rate for a given object state.
state |
Definition at line 230 of file state_getters.h.
|
inline |
Get the roll-rate for a given template object that contains an object state.
T |
obj |
Definition at line 243 of file state_getters.h.
|
inline |
Get standstill indication for a given object state.
state |
Definition at line 507 of file state_getters.h.
|
inline |
Get the standstill indication for a given template object that contains an object state.
T |
obj |
Definition at line 521 of file state_getters.h.
|
inline |
Get the ackermann steering angle for a given object state.
state |
Definition at line 345 of file state_getters.h.
|
inline |
Get the ackermann steering angle for a given template object that contains an object state.
T |
obj |
Definition at line 358 of file state_getters.h.
|
inline |
Get the front wheel angle for a given object state.
state |
Definition at line 391 of file state_getters.h.
|
inline |
Get the front wheel angle for a given template object that contains an object state.
T |
obj |
Definition at line 404 of file state_getters.h.
|
inline |
Get the steering angle rate for a given object state.
state |
Definition at line 368 of file state_getters.h.
|
inline |
Get the steering angle rate for a given template object that contains an object state.
T |
obj |
Definition at line 381 of file state_getters.h.
|
inline |
Get the rear wheel angle for a given object state.
state |
Definition at line 414 of file state_getters.h.
|
inline |
Get the rear wheel angle for a given template object that contains an object state.
T |
obj |
Definition at line 427 of file state_getters.h.
|
inline |
Get the traffic light state for a given object state.
state |
Definition at line 532 of file state_getters.h.
|
inline |
Get the traffic light state for a given template object that contains an object state.
T |
obj |
Definition at line 547 of file state_getters.h.
|
inline |
Get the traffic light type for a given object state.
state |
Definition at line 558 of file state_getters.h.
|
inline |
Get the traffic light type for a given template object that contains an object state.
T |
obj |
Definition at line 573 of file state_getters.h.
|
inline |
Get the longitudinal velocity for a given object state.
state |
Definition at line 138 of file state_getters.h.
|
inline |
Get the longitudinal velocity for a given template object that contains an object state.
T |
obj |
Definition at line 151 of file state_getters.h.
|
inline |
Get the longitudinal velocity for a given object state.
state |
Definition at line 115 of file state_getters.h.
|
inline |
Get the longitudinal velocity for a given template object that contains an object state.
T |
obj |
Definition at line 128 of file state_getters.h.
|
inline |
Get the width for a given object state.
state |
Definition at line 437 of file state_getters.h.
|
inline |
Get the width for a given template object that contains an object state.
T |
obj |
Definition at line 450 of file state_getters.h.
|
inline |
Get the x-position for a given object state.
state |
Definition at line 45 of file state_getters.h.
|
inline |
Get the x-position for a given template object that contains an object state.
T |
obj |
Definition at line 59 of file state_getters.h.
|
inline |
Get the y-position for a given object state.
state |
Definition at line 69 of file state_getters.h.
|
inline |
Get the y-position for a given template object that contains an object state.
T |
obj |
Definition at line 82 of file state_getters.h.
|
inline |
Get the yaw for a given object state.
state |
Definition at line 299 of file state_getters.h.
|
inline |
Get the yaw for a given template object that contains an object state.
T |
obj |
Definition at line 312 of file state_getters.h.
|
inline |
Get the yaw-rate for a given object state.
state |
Definition at line 322 of file state_getters.h.
|
inline |
Get the yaw-rate for a given template object that contains an object state.
T |
obj |
Definition at line 335 of file state_getters.h.
|
inline |
Get the z-position for a given object state.
state |
Definition at line 92 of file state_getters.h.
|
inline |
Get the z-position for a given template object that contains an object state.
T |
obj |
Definition at line 105 of file state_getters.h.