#include <time_change_ui.h>
Public Member Functions | |
LaneLineTimeChangeGroupUi (XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue) | |
void | updateJointStateData (const sensor_msgs::JointState::ConstPtr data, const ros::Time &time) |
![]() | |
TimeChangeGroupUi (XmlRpc::XmlRpcValue &rpc_value, Base &base, const std::string &graph_name, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue) | |
void | update () override |
void | updateForQueue () override |
![]() | |
void | add () override |
void | addForQueue (int add_times=1) override |
void | display (bool check_repeat=true) override |
void | display (const ros::Time &time) override |
void | displayTwice (bool check_repeat=true) override |
void | erasure () override |
GroupUiBase (XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr) | |
void | sendDoubleGraph (const ros::Time &time, Graph *graph0, Graph *graph1) |
void | sendFiveGraph (const ros::Time &time, Graph *graph0, Graph *graph1, Graph *graph2, Graph *graph3, Graph *graph4) |
void | sendSevenGraph (const ros::Time &time, Graph *graph0, Graph *graph1, Graph *graph2, Graph *graph3, Graph *graph4, Graph *graph5, Graph *graph6) |
void | sendUi (const ros::Time &time) override |
void | update () override |
void | updateForQueue () override |
~GroupUiBase ()=default | |
![]() | |
void | clearTxBuffer () |
void | display (const ros::Time &time, bool state, bool once=false) |
void | pack (uint8_t *tx_buffer, uint8_t *data, int cmd_id, int len) const |
void | sendCharacter (const ros::Time &time, Graph *graph) |
void | sendSerial (const ros::Time &time, int data_len) |
void | sendSingleGraph (const ros::Time &time, Graph *graph) |
UiBase (XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr) | |
virtual void | updateManualCmdData (const rm_msgs::ManualToReferee::ConstPtr data) |
virtual void | updateManualCmdData (const rm_msgs::ManualToReferee::ConstPtr data, const ros::Time &last_get_data_time) |
~UiBase ()=default | |
Protected Attributes | |
double | camera_range_ |
double | end_point_a_angle_ |
double | end_point_b_angle_ |
double | pitch_angle_ = 0. |
std::string | reference_frame_ |
double | robot_height_ |
double | robot_radius_ |
double | screen_x_ = 1920 |
double | screen_y_ = 1080 |
double | surface_coefficient_ = 0.5 |
![]() | |
std::string | graph_name_ |
![]() | |
std::map< std::string, Graph * > | character_vector_ |
std::map< std::string, Graph * > | graph_vector_ |
![]() | |
Base & | base_ |
std::deque< Graph > * | character_queue_ |
ros::Duration | delay_ = ros::Duration(0.) |
Graph * | graph_ |
std::deque< Graph > * | graph_queue_ |
const int | k_cmd_id_length_ = 2 |
const int | k_frame_length_ = 128 |
const int | k_header_length_ = 5 |
const int | k_tail_length_ = 2 |
ros::Time | last_send_ |
tf2_ros::Buffer | tf_buffer_ |
tf2_ros::TransformListener | tf_listener_ |
Private Member Functions | |
void | updateConfig () override |
Private Attributes | |
std::vector< Graph * > | lane_line_double_graph_ |
Additional Inherited Members | |
![]() | |
uint8_t | tx_buffer_ [127] |
int | tx_len_ |
![]() | |
static int | id_ |
Definition at line 132 of file time_change_ui.h.
|
inlineexplicit |
Definition at line 135 of file time_change_ui.h.
|
overrideprivatevirtual |
Reimplemented from rm_referee::TimeChangeGroupUi.
Definition at line 193 of file time_change_ui.cpp.
void rm_referee::LaneLineTimeChangeGroupUi::updateJointStateData | ( | const sensor_msgs::JointState::ConstPtr | data, |
const ros::Time & | time | ||
) |
Definition at line 226 of file time_change_ui.cpp.
|
protected |
Definition at line 169 of file time_change_ui.h.
|
protected |
Definition at line 171 of file time_change_ui.h.
|
protected |
Definition at line 171 of file time_change_ui.h.
|
private |
Definition at line 176 of file time_change_ui.h.
|
protected |
Definition at line 170 of file time_change_ui.h.
|
protected |
Definition at line 168 of file time_change_ui.h.
|
protected |
Definition at line 169 of file time_change_ui.h.
|
protected |
Definition at line 169 of file time_change_ui.h.
|
protected |
Definition at line 170 of file time_change_ui.h.
|
protected |
Definition at line 170 of file time_change_ui.h.
|
protected |
Definition at line 169 of file time_change_ui.h.