Skip to content

Commit

Permalink
Merge pull request #242 from YoujianWu/leg_cmd
Browse files Browse the repository at this point in the history
Add LegCommandSender.
  • Loading branch information
YoujianWu authored Sep 29, 2024
2 parents 4bf9a58 + 2697d1a commit 16c0838
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 0 deletions.
27 changes: 27 additions & 0 deletions rm_common/include/rm_common/decision/command_sender.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@
#include <rm_msgs/GameRobotHp.h>
#include <rm_msgs/StatusChangeRequest.h>
#include <rm_msgs/ShootData.h>
#include <rm_msgs/LegCmd.h>
#include <geometry_msgs/TwistStamped.h>
#include <sensor_msgs/JointState.h>
#include <nav_msgs/Odometry.h>
Expand Down Expand Up @@ -564,6 +565,32 @@ class BalanceCommandSender : public CommandSenderBase<std_msgs::UInt8>
void setZero() override{};
};

class LegCommandSender : public CommandSenderBase<rm_msgs::LegCmd>
{
public:
explicit LegCommandSender(ros::NodeHandle& nh) : CommandSenderBase<rm_msgs::LegCmd>(nh)
{
}

void setJump(bool jump)
{
msg_.jump = jump;
}
void setLgeLength(double length)
{
msg_.leg_length = length;
}
bool getJump()
{
return msg_.jump;
}
double getLgeLength()
{
return msg_.leg_length;
}
void setZero() override{};
};

class Vel3DCommandSender : public HeaderStampCommandSenderBase<geometry_msgs::TwistStamped>
{
public:
Expand Down
1 change: 1 addition & 0 deletions rm_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ add_message_files(
GimbalCmd.msg
GimbalDesError.msg
GimbalPosState.msg
LegCmd.msg
LpData.msg
LocalHeatState.msg
KalmanData.msg
Expand Down
2 changes: 2 additions & 0 deletions rm_msgs/msg/LegCmd.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
bool jump
float64 leg_length

0 comments on commit 16c0838

Please sign in to comment.