perception_interfaces 1.0.0
Loading...
Searching...
No Matches
Functions
state_setters.h File Reference

Setter functions for objects state members. More...

#include <perception_msgs_utils/impl/state_index.h>
#include <perception_msgs_utils/impl/checks.h>
#include <perception_msgs_utils/impl/utils.h>

Go to the source code of this file.

Functions

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.
 

Detailed Description

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.

Function Documentation

◆ setAccLat() [1/2]

void perception_msgs::object_access::setAccLat ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the lateral acceleration for a given object state.

Parameters
state
val
reset_covariance

Definition at line 210 of file state_setters.h.

210 {
212 const int idx = indexAccLat(state.model_id);
213 state.continuous_state[idx] = val;
214 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
215 }
void sanityCheckContinuousState(const ObjectState &state)
Perform sanity check on continuous state of given object state.
Definition checks.h:84
int indexAccLat(const unsigned char &model_id)
Get the vector-index that stores the lateral acceleration for a given model-id.
void setContinuousStateCovarianceToUnknownAt(ObjectState &state, const unsigned int i, const unsigned int j)
Set the continuous state covariance to unknown at (i,j) for a given object state.
Definition utils.h:174

◆ setAccLat() [2/2]

template<typename T >
void perception_msgs::object_access::setAccLat ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the lateral acceleration for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 226 of file state_setters.h.

226 {
227 setAccLat(obj.state, val, reset_covariance);
228 }
void setAccLat(ObjectState &state, const double val, const bool reset_covariance=true)
Set the lateral acceleration for a given object state.

◆ setAccLon() [1/2]

void perception_msgs::object_access::setAccLon ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the longitudinal acceleration for a given object state.

Parameters
state
val
reset_covariance

Definition at line 183 of file state_setters.h.

183 {
185 const int idx = indexAccLon(state.model_id);
186 state.continuous_state[idx] = val;
187 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
188 }
int indexAccLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal acceleration for a given model-id.

◆ setAccLon() [2/2]

template<typename T >
void perception_msgs::object_access::setAccLon ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the longitudinal acceleration for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 199 of file state_setters.h.

199 {
200 setAccLon(obj.state, val, reset_covariance);
201 }
void setAccLon(ObjectState &state, const double val, const bool reset_covariance=true)
Set the longitudinal acceleration for a given object state.

◆ setHeight() [1/2]

void perception_msgs::object_access::setHeight ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the height for a given object state.

Parameters
state
val
reset_covariance

Definition at line 570 of file state_setters.h.

570 {
572 const int idx = indexHeight(state.model_id);
573 state.continuous_state[idx] = val;
574 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
575 }
int indexHeight(const unsigned char &model_id)
Get the vector-index that stores the height for a given model-id.

◆ setHeight() [2/2]

template<typename T >
void perception_msgs::object_access::setHeight ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the height for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 586 of file state_setters.h.

586 {
587 setHeight(obj.state, val, reset_covariance);
588 }
void setHeight(ObjectState &state, const double val, const bool reset_covariance=true)
Set the height for a given object state.

◆ setLength() [1/2]

void perception_msgs::object_access::setLength ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the length for a given object state.

Parameters
state
val
reset_covariance

Definition at line 543 of file state_setters.h.

543 {
545 const int idx = indexLength(state.model_id);
546 state.continuous_state[idx] = val;
547 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
548 }
int indexLength(const unsigned char &model_id)
Get the vector-index that stores the length for a given model-id.

◆ setLength() [2/2]

template<typename T >
void perception_msgs::object_access::setLength ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the length for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 559 of file state_setters.h.

559 {
560 setLength(obj.state, val, reset_covariance);
561 }
void setLength(ObjectState &state, const double val, const bool reset_covariance=true)
Set the length for a given object state.

◆ setPitch() [1/2]

void perception_msgs::object_access::setPitch ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the pitch for a given object state.

Parameters
state
val
reset_covariance

Definition at line 294 of file state_setters.h.

294 {
296 double capped_val = val;
297 while (capped_val > M_PI) capped_val -= 2 * M_PI;
298 while (capped_val < -M_PI) capped_val += 2 * M_PI;
299 const int idx = indexPitch(state.model_id);
300 state.continuous_state[idx] = capped_val;
301 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
302 }
int indexPitch(const unsigned char &model_id)
Get the vector-index that stores the pitch for a given model-id.

◆ setPitch() [2/2]

template<typename T >
void perception_msgs::object_access::setPitch ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the pitch for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 313 of file state_setters.h.

313 {
314 setPitch(obj.state, val, reset_covariance);
315 }
void setPitch(ObjectState &state, const double val, const bool reset_covariance=true)
Set the pitch for a given object state.

◆ setPitchRate() [1/2]

void perception_msgs::object_access::setPitchRate ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the pitch-rate for a given object state.

Parameters
state
val
reset_covariance

Definition at line 324 of file state_setters.h.

324 {
326 const int idx = indexPitchRate(state.model_id);
327 state.continuous_state[idx] = val;
328 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
329 }
int indexPitchRate(const unsigned char &model_id)
Get the vector-index that stores the pitch rate for a given model-id.

◆ setPitchRate() [2/2]

template<typename T >
void perception_msgs::object_access::setPitchRate ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the pitch-rate for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 340 of file state_setters.h.

340 {
341 setPitchRate(obj.state, val, reset_covariance);
342 }
void setPitchRate(ObjectState &state, const double val, const bool reset_covariance=true)
Set the pitch-rate for a given object state.

◆ setRoll() [1/2]

void perception_msgs::object_access::setRoll ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the roll for a given object state.

Parameters
state
val
reset_covariance

Definition at line 237 of file state_setters.h.

237 {
239 double capped_val = val;
240 while (capped_val > M_PI) capped_val -= 2 * M_PI;
241 while (capped_val < -M_PI) capped_val += 2 * M_PI;
242 const int idx = indexRoll(state.model_id);
243 state.continuous_state[idx] = capped_val;
244 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
245 }
int indexRoll(const unsigned char &model_id)
Get the vector-index that stores the roll for a given model-id.

◆ setRoll() [2/2]

template<typename T >
void perception_msgs::object_access::setRoll ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the roll for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 256 of file state_setters.h.

256 {
257 setRoll(obj.state, val, reset_covariance);
258 }
void setRoll(ObjectState &state, const double val, const bool reset_covariance=true)
Set the roll for a given object state.

◆ setRollRate() [1/2]

void perception_msgs::object_access::setRollRate ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the roll-rate for a given object state.

Parameters
state
val
reset_covariance

Definition at line 267 of file state_setters.h.

267 {
269 const int idx = indexRollRate(state.model_id);
270 state.continuous_state[idx] = val;
271 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
272 }
int indexRollRate(const unsigned char &model_id)
Get the vector-index that stores the roll rate for a given model-id.

◆ setRollRate() [2/2]

template<typename T >
void perception_msgs::object_access::setRollRate ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the roll-rate for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 283 of file state_setters.h.

283 {
284 setRollRate(obj.state, val, reset_covariance);
285 }
void setRollRate(ObjectState &state, const double val, const bool reset_covariance=true)
Set the roll-rate for a given object state.

◆ setStandstill() [1/2]

void perception_msgs::object_access::setStandstill ( ObjectState &  state,
const bool  val 
)
inline

Set the standstill indication for a given object state.

Parameters
state
val

Definition at line 596 of file state_setters.h.

596 {
598 const int idx = indexStandstill(state.model_id);
599 state.discrete_state[idx] = val;
600 }
void sanityCheckDiscreteState(const ObjectState &state)
Perform sanity check on discrete state of given object state.
Definition checks.h:104
int indexStandstill(const unsigned char &model_id)
Get the vector-index that stores the standstill indication for a given model-id.

◆ setStandstill() [2/2]

template<typename T >
void perception_msgs::object_access::setStandstill ( T &  obj,
const bool  val 
)
inline

Set the standstill indication for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 610 of file state_setters.h.

610 {
611 setStandstill(obj.state, val);
612 }
void setStandstill(ObjectState &state, const bool val)
Set the standstill indication for a given object state.

◆ setSteeringAngleAck() [1/2]

void perception_msgs::object_access::setSteeringAngleAck ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the ackermann steering angle for a given object state.

Parameters
state
val
reset_covariance

Definition at line 408 of file state_setters.h.

408 {
410 const int idx = indexSteeringAngleAck(state.model_id);
411 state.continuous_state[idx] = val;
412 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
413 }
int indexSteeringAngleAck(const unsigned char &model_id)
Get the vector-index that stores the ackermann steering angle for a given model-id.

◆ setSteeringAngleAck() [2/2]

template<typename T >
void perception_msgs::object_access::setSteeringAngleAck ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the ackermann steering angle for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 424 of file state_setters.h.

424 {
425 setSteeringAngleAck(obj.state, val, reset_covariance);
426 }
void setSteeringAngleAck(ObjectState &state, const double val, const bool reset_covariance=true)
Set the ackermann steering angle for a given object state.

◆ setSteeringAngleFront() [1/2]

void perception_msgs::object_access::setSteeringAngleFront ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the front wheel angle for a given object state.

Parameters
state
val
reset_covariance

Definition at line 462 of file state_setters.h.

462 {
464 const int idx = indexSteeringAngleFront(state.model_id);
465 state.continuous_state[idx] = val;
466 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
467 }
int indexSteeringAngleFront(const unsigned char &model_id)
Get the vector-index that stores the front wheel angle for a given model-id.

◆ setSteeringAngleFront() [2/2]

template<typename T >
void perception_msgs::object_access::setSteeringAngleFront ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the front wheel angle for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 478 of file state_setters.h.

478 {
479 setSteeringAngleFront(obj.state, val, reset_covariance);
480 }
void setSteeringAngleFront(ObjectState &state, const double val, const bool reset_covariance=true)
Set the front wheel angle for a given object state.

◆ setSteeringAngleRateAck() [1/2]

void perception_msgs::object_access::setSteeringAngleRateAck ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the ackermann steering angle rate for a given object state.

Parameters
state
val
reset_covariance

Definition at line 435 of file state_setters.h.

435 {
437 const int idx = indexSteeringAngleRateAck(state.model_id);
438 state.continuous_state[idx] = val;
439 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
440 }
int indexSteeringAngleRateAck(const unsigned char &model_id)
Get the vector-index that stores the steering angle rate for a given model-id.

◆ setSteeringAngleRateAck() [2/2]

template<typename T >
void perception_msgs::object_access::setSteeringAngleRateAck ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the ackermann steering angle rate for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 451 of file state_setters.h.

451 {
452 setSteeringAngleRateAck(obj.state, val, reset_covariance);
453 }
void setSteeringAngleRateAck(ObjectState &state, const double val, const bool reset_covariance=true)
Set the ackermann steering angle rate for a given object state.

◆ setSteeringAngleRear() [1/2]

void perception_msgs::object_access::setSteeringAngleRear ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the rear wheel angle for a given object state.

Parameters
state
val
reset_covariance

Definition at line 489 of file state_setters.h.

489 {
491 const int idx = indexSteeringAngleRear(state.model_id);
492 state.continuous_state[idx] = val;
493 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
494 }
int indexSteeringAngleRear(const unsigned char &model_id)
Get the vector-index that stores the rear wheel angle for a given model-id.

◆ setSteeringAngleRear() [2/2]

template<typename T >
void perception_msgs::object_access::setSteeringAngleRear ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the rear wheel angle for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 505 of file state_setters.h.

505 {
506 setSteeringAngleRear(obj.state, val, reset_covariance);
507 }
void setSteeringAngleRear(ObjectState &state, const double val, const bool reset_covariance=true)
Set the rear wheel angle for a given object state.

◆ setTrafficLightState() [1/2]

void perception_msgs::object_access::setTrafficLightState ( ObjectState &  state,
const uint8_t  val 
)
inline

Set the traffic light state for a given object state.

Parameters
state
val

Definition at line 620 of file state_setters.h.

620 {
622 const int idx = indexTrafficLightState(state.model_id);
623 state.discrete_state[idx] = val;
624 }
int indexTrafficLightState(const unsigned char &model_id)
Get the vector-index that stores the traffic light state for a given model-id.

◆ setTrafficLightState() [2/2]

template<typename T >
void perception_msgs::object_access::setTrafficLightState ( T &  obj,
const uint8_t  val 
)
inline

Set the traffic light state for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 635 of file state_setters.h.

635 {
636 setTrafficLightState(obj.state, val);
637 }
void setTrafficLightState(ObjectState &state, const uint8_t val)
Set the traffic light state for a given object state.

◆ setTrafficLightType() [1/2]

void perception_msgs::object_access::setTrafficLightType ( ObjectState &  state,
const uint8_t  val 
)
inline

Set the traffic light type for a given object state.

Parameters
state
val

Definition at line 645 of file state_setters.h.

645 {
647 const int idx = indexTrafficLightType(state.model_id);
648 state.discrete_state[idx] = val;
649 }
int indexTrafficLightType(const unsigned char &model_id)
Get the vector-index that stores the traffic light type for a given model-id.

◆ setTrafficLightType() [2/2]

template<typename T >
void perception_msgs::object_access::setTrafficLightType ( T &  obj,
const uint8_t  val 
)
inline

Set the traffic light type for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 660 of file state_setters.h.

660 {
661 setTrafficLightType(obj.state, val);
662 }
void setTrafficLightType(ObjectState &state, const uint8_t val)
Set the traffic light type for a given object state.

◆ setVelLat() [1/2]

void perception_msgs::object_access::setVelLat ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the lateral velocity for a given object state.

Parameters
state
val
reset_covariance

Definition at line 156 of file state_setters.h.

156 {
158 const int idx = indexVelLat(state.model_id);
159 state.continuous_state[idx] = val;
160 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
161 }
int indexVelLat(const unsigned char &model_id)
Get the vector-index that stores the lateral velocity for a given model-id.

◆ setVelLat() [2/2]

template<typename T >
void perception_msgs::object_access::setVelLat ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the lateral velocity for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 172 of file state_setters.h.

172 {
173 setVelLat(obj.state, val, reset_covariance);
174 }
void setVelLat(ObjectState &state, const double val, const bool reset_covariance=true)
Set the lateral velocity for a given object state.

◆ setVelLon() [1/2]

void perception_msgs::object_access::setVelLon ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the longitdunial velocity for a given object state.

Parameters
state
val
reset_covariance

Definition at line 129 of file state_setters.h.

129 {
131 const int idx = indexVelLon(state.model_id);
132 state.continuous_state[idx] = val;
133 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
134 }
int indexVelLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal velocity for a given model-id.

◆ setVelLon() [2/2]

template<typename T >
void perception_msgs::object_access::setVelLon ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the longitudinal velocity for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 145 of file state_setters.h.

145 {
146 setVelLon(obj.state, val, reset_covariance);
147 }
void setVelLon(ObjectState &state, const double val, const bool reset_covariance=true)
Set the longitdunial velocity for a given object state.

◆ setWidth() [1/2]

void perception_msgs::object_access::setWidth ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the width for a given object state.

Parameters
state
val
reset_covariance

Definition at line 516 of file state_setters.h.

516 {
518 const int idx = indexWidth(state.model_id);
519 state.continuous_state[idx] = val;
520 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
521 }
int indexWidth(const unsigned char &model_id)
Get the vector-index that stores the width for a given model-id.

◆ setWidth() [2/2]

template<typename T >
void perception_msgs::object_access::setWidth ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the width for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 532 of file state_setters.h.

532 {
533 setWidth(obj.state, val, reset_covariance);
534 }
void setWidth(ObjectState &state, const double val, const bool reset_covariance=true)
Set the width for a given object state.

◆ setX() [1/2]

void perception_msgs::object_access::setX ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the x-position for a given object state.

Parameters
state
val
reset_covariance

Definition at line 48 of file state_setters.h.

48 {
50 const int idx = indexX(state.model_id);
51 state.continuous_state[idx] = val;
52 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
53 }
int indexX(const unsigned char &model_id)
Get the vector-index that stores the x-position for a given model-id.
Definition state_index.h:45

◆ setX() [2/2]

template<typename T >
void perception_msgs::object_access::setX ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the x-position for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 64 of file state_setters.h.

64 {
65 setX(obj.state, val, reset_covariance);
66 }
void setX(ObjectState &state, const double val, const bool reset_covariance=true)
Set the x-position for a given object state.

◆ setY() [1/2]

void perception_msgs::object_access::setY ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the y-position for a given object state.

Parameters
state
val
reset_covariance

Definition at line 75 of file state_setters.h.

75 {
77 const int idx = indexY(state.model_id);
78 state.continuous_state[idx] = val;
79 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
80 }
int indexY(const unsigned char &model_id)
Get the vector-index that stores the y-position for a given model-id.
Definition state_index.h:68

◆ setY() [2/2]

template<typename T >
void perception_msgs::object_access::setY ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the y-position for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 91 of file state_setters.h.

91 {
92 setY(obj.state, val, reset_covariance);
93 }
void setY(ObjectState &state, const double val, const bool reset_covariance=true)
Set the y-position for a given object state.

◆ setYaw() [1/2]

void perception_msgs::object_access::setYaw ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the yaw for a given object state.

Parameters
state
val
reset_covariance

Definition at line 351 of file state_setters.h.

351 {
353 double capped_val = val;
354 while (capped_val > M_PI) capped_val -= 2 * M_PI;
355 while (capped_val < -M_PI) capped_val += 2 * M_PI;
356 const int idx = indexYaw(state.model_id);
357 state.continuous_state[idx] = capped_val;
358 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
359 }
int indexYaw(const unsigned char &model_id)
Get the vector-index that stores the yaw for a given model-id.

◆ setYaw() [2/2]

template<typename T >
void perception_msgs::object_access::setYaw ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the yaw for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 370 of file state_setters.h.

370 {
371 setYaw(obj.state, val, reset_covariance);
372 }
void setYaw(ObjectState &state, const double val, const bool reset_covariance=true)
Set the yaw for a given object state.

◆ setYawRate() [1/2]

void perception_msgs::object_access::setYawRate ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the yaw-rate for a given object state.

Parameters
state
val
reset_covariance

Definition at line 381 of file state_setters.h.

381 {
383 const int idx = indexYawRate(state.model_id);
384 state.continuous_state[idx] = val;
385 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
386 }
int indexYawRate(const unsigned char &model_id)
Get the vector-index that stores the yaw-rate for a given model-id.

◆ setYawRate() [2/2]

template<typename T >
void perception_msgs::object_access::setYawRate ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the yaw-rate for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 397 of file state_setters.h.

397 {
398 setYawRate(obj.state, val, reset_covariance);
399 }
void setYawRate(ObjectState &state, const double val, const bool reset_covariance=true)
Set the yaw-rate for a given object state.

◆ setZ() [1/2]

void perception_msgs::object_access::setZ ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the z-position for a given object state.

Parameters
state
val
reset_covariance

Definition at line 102 of file state_setters.h.

102 {
104 const int idx = indexZ(state.model_id);
105 state.continuous_state[idx] = val;
106 if (reset_covariance) setContinuousStateCovarianceToUnknownAt(state, idx, idx);
107 }
int indexZ(const unsigned char &model_id)
Get the vector-index that stores the z-position for a given model-id.
Definition state_index.h:91

◆ setZ() [2/2]

template<typename T >
void perception_msgs::object_access::setZ ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the z-position for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 118 of file state_setters.h.

118 {
119 setZ(obj.state, val, reset_covariance);
120 }
void setZ(ObjectState &state, const double val, const bool reset_covariance=true)
Set the z-position for a given object state.