parent
c36a2acf98
commit
57fc6b6308
|
@ -3,7 +3,6 @@
|
||||||
UnitreeSdk2Bridge::UnitreeSdk2Bridge(mjModel *model, mjData *data) : mj_model_(model), mj_data_(data)
|
UnitreeSdk2Bridge::UnitreeSdk2Bridge(mjModel *model, mjData *data) : mj_model_(model), mj_data_(data)
|
||||||
{
|
{
|
||||||
CheckSensor();
|
CheckSensor();
|
||||||
SetupJoystick();
|
|
||||||
|
|
||||||
if (idl_type_ == 0)
|
if (idl_type_ == 0)
|
||||||
{
|
{
|
||||||
|
@ -387,4 +386,4 @@ void UnitreeSdk2Bridge::GetWirelessRemote()
|
||||||
wireless_remote_.ly = -double(js_->axis_[js_id_.axis["LY"]]) / max_value_;
|
wireless_remote_.ly = -double(js_->axis_[js_id_.axis["LY"]]) / max_value_;
|
||||||
wireless_remote_.rx = double(js_->axis_[js_id_.axis["RX"]]) / max_value_;
|
wireless_remote_.rx = double(js_->axis_[js_id_.axis["RX"]]) / max_value_;
|
||||||
wireless_remote_.ry = -double(js_->axis_[js_id_.axis["RY"]]) / max_value_;
|
wireless_remote_.ry = -double(js_->axis_[js_id_.axis["RY"]]) / max_value_;
|
||||||
}
|
}
|
|
@ -110,7 +110,7 @@ public:
|
||||||
void Run();
|
void Run();
|
||||||
void PrintSceneInformation();
|
void PrintSceneInformation();
|
||||||
void CheckSensor();
|
void CheckSensor();
|
||||||
void SetupJoystick(string device = "/dev/input/js0", string js_type = "xbox", int bits = 16);
|
void SetupJoystick(string device, string js_type, int bits);
|
||||||
|
|
||||||
ChannelSubscriberPtr<unitree_go::msg::dds_::LowCmd_> low_cmd_go_suber_;
|
ChannelSubscriberPtr<unitree_go::msg::dds_::LowCmd_> low_cmd_go_suber_;
|
||||||
ChannelSubscriberPtr<unitree_hg::msg::dds_::LowCmd_> low_cmd_hg_suber_;
|
ChannelSubscriberPtr<unitree_hg::msg::dds_::LowCmd_> low_cmd_hg_suber_;
|
||||||
|
|
Loading…
Reference in New Issue