|
void | perception_msgs::object_access::setX (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the x-position for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setX (T &obj, const double val, const bool reset_covariance=true) |
| Set the x-position for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setY (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the y-position for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setY (T &obj, const double val, const bool reset_covariance=true) |
| Set the y-position for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setZ (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the z-position for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setZ (T &obj, const double val, const bool reset_covariance=true) |
| Set the z-position for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setVelLon (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the longitdunial velocity for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setVelLon (T &obj, const double val, const bool reset_covariance=true) |
| Set the longitudinal velocity for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setVelLat (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the lateral velocity for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setVelLat (T &obj, const double val, const bool reset_covariance=true) |
| Set the lateral velocity for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setAccLon (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the longitudinal acceleration for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setAccLon (T &obj, const double val, const bool reset_covariance=true) |
| Set the longitudinal acceleration for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setAccLat (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the lateral acceleration for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setAccLat (T &obj, const double val, const bool reset_covariance=true) |
| Set the lateral acceleration for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setRoll (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the roll for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setRoll (T &obj, const double val, const bool reset_covariance=true) |
| Set the roll for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setRollRate (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the roll-rate for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setRollRate (T &obj, const double val, const bool reset_covariance=true) |
| Set the roll-rate for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setPitch (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the pitch for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setPitch (T &obj, const double val, const bool reset_covariance=true) |
| Set the pitch for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setPitchRate (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the pitch-rate for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setPitchRate (T &obj, const double val, const bool reset_covariance=true) |
| Set the pitch-rate for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setYaw (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the yaw for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setYaw (T &obj, const double val, const bool reset_covariance=true) |
| Set the yaw for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setYawRate (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the yaw-rate for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setYawRate (T &obj, const double val, const bool reset_covariance=true) |
| Set the yaw-rate for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setSteeringAngleAck (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the ackermann steering angle for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setSteeringAngleAck (T &obj, const double val, const bool reset_covariance=true) |
| Set the ackermann steering angle for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setSteeringAngleRateAck (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the ackermann steering angle rate for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setSteeringAngleRateAck (T &obj, const double val, const bool reset_covariance=true) |
| Set the ackermann steering angle rate for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setSteeringAngleFront (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the front wheel angle for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setSteeringAngleFront (T &obj, const double val, const bool reset_covariance=true) |
| Set the front wheel angle for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setSteeringAngleRear (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the rear wheel angle for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setSteeringAngleRear (T &obj, const double val, const bool reset_covariance=true) |
| Set the rear wheel angle for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setWidth (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the width for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setWidth (T &obj, const double val, const bool reset_covariance=true) |
| Set the width for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setLength (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the length for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setLength (T &obj, const double val, const bool reset_covariance=true) |
| Set the length for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setHeight (ObjectState &state, const double val, const bool reset_covariance=true) |
| Set the height for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setHeight (T &obj, const double val, const bool reset_covariance=true) |
| Set the height for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setStandstill (ObjectState &state, const bool val) |
| Set the standstill indication for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setStandstill (T &obj, const bool val) |
| Set the standstill indication for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setTrafficLightState (ObjectState &state, const uint8_t val) |
| Set the traffic light state for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setTrafficLightState (T &obj, const uint8_t val) |
| Set the traffic light state for a given template object that contains an object state.
|
|
void | perception_msgs::object_access::setTrafficLightType (ObjectState &state, const uint8_t val) |
| Set the traffic light type for a given object state.
|
|
template<typename T > |
void | perception_msgs::object_access::setTrafficLightType (T &obj, const uint8_t val) |
| Set the traffic light type for a given template object that contains an object state.
|
|
Setter 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
SOFTWARE.
Definition in file state_setters.h.