Skip to content

Commit

Permalink
feat: add gazebo service
Browse files Browse the repository at this point in the history
  • Loading branch information
fan-ziqi committed May 25, 2024
1 parent e387389 commit dc10d01
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 1 deletion.
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -7,5 +7,5 @@ logs
*lite3*
*fldlar*
.cache
.json
*.json
# *gr1t1*
2 changes: 2 additions & 0 deletions src/rl_sar/include/rl_sim.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include <ros/ros.h>
#include <gazebo_msgs/ModelStates.h>
#include <sensor_msgs/JointState.h>
#include "std_srvs/Empty.h"
#include <geometry_msgs/Twist.h>
#include "robot_msgs/MotorCommand.h"
#include <csignal>
Expand Down Expand Up @@ -55,6 +56,7 @@ class RL_Sim : public RL
ros::Subscriber joint_state_subscriber;
ros::Subscriber cmd_vel_subscriber;
std::map<std::string, ros::Publisher> torque_publishers;
ros::ServiceClient gazebo_reset_client;
void ModelStatesCallback(const gazebo_msgs::ModelStates::ConstPtr &msg);
void JointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg);
void CmdvelCallback(const geometry_msgs::Twist::ConstPtr &msg);
Expand Down
1 change: 1 addition & 0 deletions src/rl_sar/library/rl_sdk/rl_sdk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,6 +242,7 @@ void RL::RunKeyboard()
case 'j': keyboard.y += 0.1; break;
case 'l': keyboard.y -= 0.1; break;
case ' ': keyboard.x = 0; keyboard.y = 0; keyboard.yaw = 0; break;
case 'r': keyboard.keyboard_state = STATE_RESET_SIMULATION; break;
default: break;
}
}
Expand Down
1 change: 1 addition & 0 deletions src/rl_sar/library/rl_sdk/rl_sdk.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ enum STATE {
STATE_RL_INIT,
STATE_RL_RUNNING,
STATE_POS_GETDOWN,
STATE_RESET_SIMULATION,
};

struct KeyBoard
Expand Down
10 changes: 10 additions & 0 deletions src/rl_sar/src/rl_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,9 @@ RL_Sim::RL_Sim()
model_state_subscriber = nh.subscribe<gazebo_msgs::ModelStates>("/gazebo/model_states", 10, &RL_Sim::ModelStatesCallback, this);
joint_state_subscriber = nh.subscribe<sensor_msgs::JointState>(ros_namespace + "joint_states", 10, &RL_Sim::JointStatesCallback, this);

// service
gazebo_reset_client = nh.serviceClient<std_srvs::Empty>("/gazebo/reset_simulation");

// loop
loop_keyboard = std::make_shared<LoopFunc>("loop_keyboard", 0.05 , boost::bind(&RL_Sim::RunKeyboard, this));
loop_control = std::make_shared<LoopFunc>("loop_control" , 0.002, boost::bind(&RL_Sim::RobotControl, this));
Expand Down Expand Up @@ -135,6 +138,13 @@ void RL_Sim::RobotControl()

motiontime++;

if(keyboard.keyboard_state == STATE_RESET_SIMULATION)
{
keyboard.keyboard_state = STATE_WAITING;
std_srvs::Empty srv;
gazebo_reset_client.call(srv);
}

GetState(&robot_state);
StateController(&robot_state, &robot_command);
SetCommand(&robot_command);
Expand Down

0 comments on commit dc10d01

Please sign in to comment.