File tree Expand file tree Collapse file tree 4 files changed +35
-3
lines changed
rm_common/include/rm_common/decision Expand file tree Collapse file tree 4 files changed +35
-3
lines changed Original file line number Diff line number Diff line change 1414
1515repos :
1616 # Standard hooks
17- - repo : https:// github.com/ pre-commit/pre-commit-hooks
17+ - repo : git@ github.com: pre-commit/pre-commit-hooks.git
1818 rev : v4.0.1
1919 hooks :
2020 - id : check-added-large-files
@@ -28,12 +28,12 @@ repos:
2828 - id : mixed-line-ending
2929 - id : trailing-whitespace
3030
31- - repo : https:// github.com/ psf/black
31+ - repo : git@ github.com: psf/black
3232 rev : 20.8b1
3333 hooks :
3434 - id : black
3535
36- - repo : https:// github.com/ Lucas-C/pre-commit-hooks-markup
36+ - repo : git@ github.com: Lucas-C/pre-commit-hooks-markup
3737 rev : v1.0.1
3838 hooks :
3939 - id : rst-linter
Original file line number Diff line number Diff line change 5151#include < rm_msgs/GameRobotHp.h>
5252#include < rm_msgs/StatusChangeRequest.h>
5353#include < rm_msgs/ShootData.h>
54+ #include < rm_msgs/LegCmd.h>
5455#include < geometry_msgs/TwistStamped.h>
5556#include < sensor_msgs/JointState.h>
5657#include < nav_msgs/Odometry.h>
@@ -564,6 +565,32 @@ class BalanceCommandSender : public CommandSenderBase<std_msgs::UInt8>
564565 void setZero () override {};
565566};
566567
568+ class LegCommandSender : public CommandSenderBase <rm_msgs::LegCmd>
569+ {
570+ public:
571+ explicit LegCommandSender (ros::NodeHandle& nh) : CommandSenderBase<rm_msgs::LegCmd>(nh)
572+ {
573+ }
574+
575+ void setJump (bool jump)
576+ {
577+ msg_.jump = jump;
578+ }
579+ void setLgeLength (double length)
580+ {
581+ msg_.leg_length = length;
582+ }
583+ bool getJump ()
584+ {
585+ return msg_.jump ;
586+ }
587+ double getLgeLength ()
588+ {
589+ return msg_.leg_length ;
590+ }
591+ void setZero () override {};
592+ };
593+
567594class Vel3DCommandSender : public HeaderStampCommandSenderBase <geometry_msgs::TwistStamped>
568595{
569596public:
Original file line number Diff line number Diff line change @@ -22,6 +22,7 @@ add_message_files(
2222 GimbalCmd.msg
2323 GimbalDesError.msg
2424 GimbalPosState.msg
25+ LegCmd.msg
2526 LpData.msg
2627 LocalHeatState.msg
2728 KalmanData.msg
Original file line number Diff line number Diff line change 1+ bool jump
2+ float64 leg_length
3+
4+ time stamp
You can’t perform that action at this time.
0 commit comments