GAMS
1.4.0
|
Internal class implementing coordinates bound to reference frame. More...
#include <Framed.h>
Public Types | |
using | derived_type = typename Impl::derived_type |
Public Member Functions | |
Framed ()=default | |
Default Constructor. More... | |
template<typename... Args> | |
Framed (Args &&... args) | |
Construct without a ReferenceFrame object. More... | |
Framed (ReferenceFrame frame) | |
Construct using just a ReferenceFrame object. More... | |
template<typename... Args> | |
Framed (ReferenceFrame frame, Args &&... args) | |
Construct using a ReferenceFrame object. More... | |
template<typename Base2 > | |
bool | approximately_equal (const Framed< Base2 > &other, double epsilon) const |
Tests if this Coordinate is within epsilon in distance (as defined by this Coordinate's reference frame's distance metric). More... | |
double | distance_to (const derived_type &target) const |
Calculate distance from this Coordinate to a target. More... | |
const ReferenceFrame & | frame () const |
Getter for the ReferenceFrame this Coordinate belongs to. More... | |
ReferenceFrame | frame (ReferenceFrame new_frame) |
Setter for the ReferenceFrame this Coordinate belongs to. More... | |
void | normalize () |
Reduces this Coordinate to it's normalized form, should one exist. More... | |
void | transform_this_to (const ReferenceFrame &new_frame) |
Transform this coordinate, in place, to a new reference frame. More... | |
derived_type WARN_UNUSED | transform_to (const ReferenceFrame &new_frame) const |
Copy and transform this coordinate to a new reference frame. More... | |
Private Attributes | |
ReferenceFrame | frame_ = default_frame() |
Internal class implementing coordinates bound to reference frame.
Do not use directly.
using gams::pose::Framed< Impl >::derived_type = typename Impl::derived_type |
|
default |
Default Constructor.
Initializes frame as empty
gams::pose::Framed< Impl >::Framed | ( | Args &&... | args | ) |
Construct without a ReferenceFrame object.
Initialized frame as empty, unless at least one argument is a type which includes a frame, in which case that frame will become the frame of this pose. If multiple do, the first such argument will be used.
This overload only participates if the first argument isn't ReferenceFrame
args | arguments to pass through to base type |
|
inlineexplicit |
Construct using just a ReferenceFrame object.
All coordinate values zero.
frame | the ReferenceFrame this Coordinate will belong to |
gams::pose::Framed< Impl >::Framed | ( | ReferenceFrame | frame, |
Args &&... | args | ||
) |
Construct using a ReferenceFrame object.
frame | the ReferenceFrame this Coordinate will belong to |
args | arguments to pass through to base type. Any types that have a reference frame associated will be transformed into frame first. To avoid this, use the non-framed *Vector types. |
|
inline |
Tests if this Coordinate is within epsilon in distance (as defined by this Coordinate's reference frame's distance metric).
If the other Coordinate is in a different reference frame, it is first copied, and converted to this Coordinate's reference frame.
other | the other Coordinate to test against |
epsilon | the maximum distance permitted to return true |
double gams::pose::Framed< Impl >::distance_to | ( | const derived_type & | target | ) | const |
Calculate distance from this Coordinate to a target.
If the target is in another reference frame, this and the target will be copied, and converted to their closest common frame.
Requres "ReferenceFrame.h"
target | the target Coordinate to calculate distance to |
unrelated_frames | thrown if the target's reference frame is not part of the same tree as the current one. |
undefined_transform | thrown if no conversion between two frames along the conversion path has been defined. |
|
inline |
Getter for the ReferenceFrame this Coordinate belongs to.
|
inline |
Setter for the ReferenceFrame this Coordinate belongs to.
Any further calculations using this Coordinate will use this frame.
Not thread-safe.
new_frame | the frame the Coordinate will now belong to |
void gams::pose::Framed< Impl >::normalize | ( | ) |
Reduces this Coordinate to it's normalized form, should one exist.
Typically useful for Coordinate types which incorporate angles.
Requres "ReferenceFrame.h"
void gams::pose::Framed< Impl >::transform_this_to | ( | const ReferenceFrame & | new_frame | ) |
Transform this coordinate, in place, to a new reference frame.
Requres "ReferenceFrame.h"
new_frame | the frame to transform to |
unrelated_frames | thrown if the new reference frame is not part of the same tree as the current one. |
undefined_transform | thrown if no conversion between two frames along the conversion path has been defined. |
derived_type WARN_UNUSED gams::pose::Framed< Impl >::transform_to | ( | const ReferenceFrame & | new_frame | ) | const |
Copy and transform this coordinate to a new reference frame.
Requres "ReferenceFrame.h"
new_frame | the frame to transform to |
unrelated_frames | thrown if the new reference frame is not part of the same tree as the current one. |
undefined_transform | thrown if no conversion between two frames along the conversion path has been defined. |
|
private |