Ligament node on a Mechanism2d.
More...
#include <frc/smartdashboard/MechanismLigament2d.h>
|
| MechanismLigament2d (std::string_view name, double length, units::degree_t angle, double lineWidth=6, const frc::Color8Bit &color={235, 137, 52}) |
|
void | SetColor (const Color8Bit &color) |
| Set the ligament color. More...
|
|
Color8Bit | GetColor () |
| Get the ligament color. More...
|
|
void | SetLength (double length) |
| Set the ligament's length. More...
|
|
double | GetLength () |
| Get the ligament length. More...
|
|
void | SetAngle (units::degree_t angle) |
| Set the ligament's angle relative to its parent. More...
|
|
double | GetAngle () |
| Get the ligament's angle relative to its parent. More...
|
|
void | SetLineWeight (double lineWidth) |
| Set the line thickness. More...
|
|
double | GetLineWeight () |
| Get the line thickness. More...
|
|
virtual | ~MechanismObject2d ()=default |
|
const std::string & | GetName () const |
| Retrieve the object's name. More...
|
|
template<typename T , typename... Args, typename = std::enable_if_t<std::is_convertible_v<T*, MechanismObject2d*>>> |
T * | Append (std::string_view name, Args &&... args) |
| Append a Mechanism object that is based on this one. More...
|
|
Ligament node on a Mechanism2d.
A ligament can have its length changed (like an elevator) or angle changed, like an arm.
- See also
- Mechanism2d
◆ MechanismLigament2d()
frc::MechanismLigament2d::MechanismLigament2d |
( |
std::string_view |
name, |
|
|
double |
length, |
|
|
units::degree_t |
angle, |
|
|
double |
lineWidth = 6 , |
|
|
const frc::Color8Bit & |
color = {235, 137, 52} |
|
) |
| |
◆ GetAngle()
double frc::MechanismLigament2d::GetAngle |
( |
| ) |
|
Get the ligament's angle relative to its parent.
- Returns
- the angle
◆ GetColor()
Color8Bit frc::MechanismLigament2d::GetColor |
( |
| ) |
|
Get the ligament color.
- Returns
- the color of the line
◆ GetLength()
double frc::MechanismLigament2d::GetLength |
( |
| ) |
|
Get the ligament length.
- Returns
- the line length
◆ GetLineWeight()
double frc::MechanismLigament2d::GetLineWeight |
( |
| ) |
|
Get the line thickness.
- Returns
- the line thickness
◆ SetAngle()
void frc::MechanismLigament2d::SetAngle |
( |
units::degree_t |
angle | ) |
|
Set the ligament's angle relative to its parent.
- Parameters
-
◆ SetColor()
void frc::MechanismLigament2d::SetColor |
( |
const Color8Bit & |
color | ) |
|
Set the ligament color.
- Parameters
-
color | the color of the line |
◆ SetLength()
void frc::MechanismLigament2d::SetLength |
( |
double |
length | ) |
|
Set the ligament's length.
- Parameters
-
◆ SetLineWeight()
void frc::MechanismLigament2d::SetLineWeight |
( |
double |
lineWidth | ) |
|
Set the line thickness.
- Parameters
-
lineWidth | the line thickness |
◆ UpdateEntries()
void frc::MechanismLigament2d::UpdateEntries |
( |
std::shared_ptr< nt::NetworkTable > |
table | ) |
|
|
overrideprotectedvirtual |
The documentation for this class was generated from the following file: