WPILibC++ 2024.3.2
MechanismLigament2d.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <memory>
8#include <string_view>
9
12#include <units/angle.h>
13
15#include "frc/util/Color8Bit.h"
16
17namespace frc {
18
19/**
20 * Ligament node on a Mechanism2d.
21 *
22 * A ligament can have its length changed (like an elevator) or angle changed,
23 * like an arm.
24 *
25 * @see Mechanism2d
26 */
28 public:
30 units::degree_t angle, double lineWidth = 6,
31 const frc::Color8Bit& color = {235, 137, 52});
32
33 /**
34 * Set the ligament color.
35 *
36 * @param color the color of the line
37 */
38 void SetColor(const Color8Bit& color);
39
40 /**
41 * Get the ligament color.
42 *
43 * @return the color of the line
44 */
46
47 /**
48 * Set the ligament's length.
49 *
50 * @param length the line length
51 */
52 void SetLength(double length);
53
54 /**
55 * Get the ligament length.
56 *
57 * @return the line length
58 */
59 double GetLength();
60
61 /**
62 * Set the ligament's angle relative to its parent.
63 *
64 * @param angle the angle
65 */
66 void SetAngle(units::degree_t angle);
67
68 /**
69 * Get the ligament's angle relative to its parent.
70 *
71 * @return the angle
72 */
73 double GetAngle();
74
75 /**
76 * Set the line thickness.
77 *
78 * @param lineWidth the line thickness
79 */
80 void SetLineWeight(double lineWidth);
81
82 /**
83 * Get the line thickness.
84 *
85 * @return the line thickness
86 */
87 double GetLineWeight();
88
89 protected:
90 void UpdateEntries(std::shared_ptr<nt::NetworkTable> table) override;
91
92 private:
93 nt::StringPublisher m_typePub;
94 double m_length;
95 nt::DoubleEntry m_lengthEntry;
96 double m_angle;
97 nt::DoubleEntry m_angleEntry;
98 double m_weight;
99 nt::DoubleEntry m_weightEntry;
100 char m_color[10];
101 nt::StringEntry m_colorEntry;
102};
103} // namespace frc
Represents colors that can be used with Addressable LEDs.
Definition: Color8Bit.h:23
Ligament node on a Mechanism2d.
Definition: MechanismLigament2d.h:27
void SetAngle(units::degree_t angle)
Set the ligament's angle relative to its parent.
void SetLineWeight(double lineWidth)
Set the line thickness.
Color8Bit GetColor()
Get the ligament color.
void SetColor(const Color8Bit &color)
Set the ligament color.
void SetLength(double length)
Set the ligament's length.
void UpdateEntries(std::shared_ptr< nt::NetworkTable > table) override
Update all entries with new ones from a new table.
double GetLineWeight()
Get the line thickness.
MechanismLigament2d(std::string_view name, double length, units::degree_t angle, double lineWidth=6, const frc::Color8Bit &color={235, 137, 52})
double GetLength()
Get the ligament length.
double GetAngle()
Get the ligament's angle relative to its parent.
Common base class for all Mechanism2d node types.
Definition: MechanismObject2d.h:31
NetworkTables Double entry.
Definition: DoubleTopic.h:162
NetworkTables String entry.
Definition: StringTopic.h:214
NetworkTables String publisher.
Definition: StringTopic.h:162
basic_string_view< char > string_view
Definition: core.h:501
Definition: AprilTagPoseEstimator.h:15
color
Definition: color.h:16