Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add LegCommandSender. #242

Merged
merged 4 commits into from
Sep 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading