Skip to content

Commit

Permalink
Update rm_referee for engineer, radar and sentry.
Browse files Browse the repository at this point in the history
  • Loading branch information
GuraMumei committed Apr 16, 2024
1 parent 96c3b3a commit 5242d1e
Show file tree
Hide file tree
Showing 6 changed files with 57 additions and 3 deletions.
3 changes: 2 additions & 1 deletion rm_referee/include/rm_referee/common/protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,8 @@ typedef enum
BLUE_STANDARD_3_CLIENT = 0x0167,
BLUE_STANDARD_4_CLIENT = 0x0168,
BLUE_STANDARD_5_CLIENT = 0x0169,
BLUE_AERIAL_CLIENT = 0x016A
BLUE_AERIAL_CLIENT = 0x016A,
REFEREE_SERVER = 0x8080
} ClientId;

typedef enum
Expand Down
3 changes: 3 additions & 0 deletions rm_referee/include/rm_referee/referee_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,9 @@ class RefereeBase
PitchAngleTimeChangeUi* pitch_angle_time_change_ui_{};
JointPositionTimeChangeUi *engineer_joint1_time_change_ui{}, *engineer_joint2_time_change_ui{},
*engineer_joint3_time_change_ui{};
StringTriggerChangeUi *step_name_trigger_change_ui_{}, *servo_mode_trigger_change_ui_{},
*reversal_state_trigger_change_ui_{}, *stone_num_trigger_change_ui_{}, *joint_temperature_trigger_change_ui_{},
*drag_state_trigger_change_ui_{}, *gripper_state_trigger_change_ui_{};

FixedUi* fixed_ui_{};

Expand Down
12 changes: 12 additions & 0 deletions rm_referee/include/rm_referee/ui/trigger_change_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -226,4 +226,16 @@ class CameraTriggerChangeUi : public TriggerChangeUi
std::string current_camera_{}, camera1_name_{}, camera2_name_{};
};

class StringTriggerChangeUi : public TriggerChangeUi
{
public:
explicit StringTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& name,
std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
: TriggerChangeUi(rpc_value, base, name, graph_queue, character_queue){};
void updateStringUiData(const std::string& data);

private:
void update() override;
std::string data_;
};
} // namespace rm_referee
24 changes: 24 additions & 0 deletions rm_referee/src/referee_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,22 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
new TargetViewAngleTriggerChangeUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "camera")
camera_trigger_change_ui_ = new CameraTriggerChangeUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
// if (rpc_value[i]["name"] == "drag")
// drag_state_trigger_change_ui_ =
// new StringTriggerChangeUi(rpc_value[i], base_, &graph_queue_, &character_queue_, "drag");
if (rpc_value[i]["name"] == "gripper")
gripper_state_trigger_change_ui_ =
new StringTriggerChangeUi(rpc_value[i], base_, "gripper", &graph_queue_, &character_queue_);
// if (rpc_value[i]["name"] == "step")
// step_name_trigger_change_ui_ = new StringTriggerChangeUi(rpc_value[i], base_, "step");
// if (rpc_value[i]["name"] == "reversal")
// reversal_state_trigger_change_ui_ = new StringTriggerChangeUi(rpc_value[i], base_, "reversal");
// if (rpc_value[i]["name"] == "stone")
// stone_num_trigger_change_ui_ = new StringTriggerChangeUi(rpc_value[i], base_, "stone");
// if (rpc_value[i]["name"] == "temperature")
// joint_temperature_trigger_change_ui_ = new StringTriggerChangeUi(rpc_value[i], base_, "temperature");
// if (rpc_value[i]["name"] == "servo_mode")
// servo_mode_trigger_change_ui_ = new StringTriggerChangeUi(rpc_value[i], base_, "mode");
}

ui_nh.getParam("time_change", rpc_value);
Expand Down Expand Up @@ -177,6 +193,10 @@ void RefereeBase::addUi()
engineer_joint2_time_change_ui->addForQueue();
if (engineer_joint3_time_change_ui)
engineer_joint3_time_change_ui->addForQueue();
if (drag_state_trigger_change_ui_)
drag_state_trigger_change_ui_->addForQueue();
if (gripper_state_trigger_change_ui_)
gripper_state_trigger_change_ui_->addForQueue();
if (bullet_time_change_ui_)
{
bullet_time_change_ui_->reset();
Expand Down Expand Up @@ -387,6 +407,10 @@ void RefereeBase::engineerUiDataCallback(const rm_msgs::EngineerUi::ConstPtr& da
{
/*if (progress_time_change_ui_ && !is_adding_)
progress_time_change_ui_->updateEngineerUiData(data, ros::Time::now());*/
/* if (drag_state_trigger_change_ui_ && !is_adding_)
drag_state_trigger_change_ui_->updateStringUiData(data->drag_state);*/
if (gripper_state_trigger_change_ui_ && !is_adding_)
gripper_state_trigger_change_ui_->updateStringUiData(data->gripper_state);
}
void RefereeBase::manualDataCallBack(const rm_msgs::ManualToReferee::ConstPtr& data)
{
Expand Down
14 changes: 14 additions & 0 deletions rm_referee/src/ui/trigger_change_ui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -422,4 +422,18 @@ void CameraTriggerChangeUi::update()
graph_->setOperation(rm_referee::GraphOperation::UPDATE);
updateForQueue(true);
}

void StringTriggerChangeUi::updateStringUiData(const std::string& data)
{
data_ = data;
update();
}

void StringTriggerChangeUi::update()
{
graph_->setContent(data_);
graph_->setColor(rm_referee::GraphColor::GREEN);
graph_->setOperation(rm_referee::GraphOperation::UPDATE);
updateForQueue(true);
}
} // namespace rm_referee
4 changes: 2 additions & 2 deletions rm_referee/src/ui/ui_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,7 +327,7 @@ void UiBase::sendSentryCmdData(const rm_msgs::SentryInfoConstPtr& data)
data_len = static_cast<int>(sizeof(rm_referee::SentryInfo));

tx_data.header.sender_id = base_.robot_id_;
tx_data.header.receiver_id = base_.client_id_;
tx_data.header.receiver_id = REFEREE_SERVER;
tx_data.sentry_info = data->sentry_info;

tx_data.header.data_cmd_id = rm_referee::DataCmdId::SENTRY_CMD;
Expand All @@ -342,7 +342,7 @@ void UiBase::sendRadarCmdData(const rm_msgs::RadarInfoConstPtr& data)
data_len = static_cast<int>(sizeof(rm_referee::RadarInfo));

tx_data.header.sender_id = base_.robot_id_;
tx_data.header.receiver_id = base_.client_id_;
tx_data.header.receiver_id = REFEREE_SERVER;
tx_data.radar_info = data->radar_info;

tx_data.header.data_cmd_id = rm_referee::DataCmdId::RADAR_CMD;
Expand Down

0 comments on commit 5242d1e

Please sign in to comment.