-
Notifications
You must be signed in to change notification settings - Fork 34
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #557 from sugikazu75/develop/mujoco
[MuJoCo] enable to use mujoco simulator
- Loading branch information
Showing
49 changed files
with
676 additions
and
32 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -107,3 +107,7 @@ tags | |
# Jetbrains | ||
.idea/ | ||
*cmake-build-debug/ | ||
|
||
# mujoco | ||
MUJOCO_LOG.txt | ||
robots/**/mujoco |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1 @@ | ||
build |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
File renamed without changes.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,17 @@ | ||
# control | ||
attitude_controller: | ||
type: flight_controllers/MujocoAttitudeController | ||
|
||
|
||
# sensor -> aerial_robot_hw_sim | ||
## mocap | ||
simulation: | ||
robot_hw_sim_plugin_name: mujoco_ros_control/AerialRobotHWSim | ||
|
||
mocap_pub_rate: 0.01 | ||
mocap_pos_noise: 0.001 | ||
mocap_rot_noise: 0.001 | ||
|
||
# ground truth -> aerial_robot_hw_sim | ||
ground_truth_pub_rate: 0.01 | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
43 changes: 43 additions & 0 deletions
43
aerial_robot_simulation/include/aerial_robot_simulation/mujoco/mujoco_aerial_robot_hw_sim.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,43 @@ | ||
#pragma once | ||
|
||
#include <aerial_robot_simulation/mujoco/mujoco_spinal_interface.h> | ||
#include <aerial_robot_simulation/noise_model.h> | ||
#include <geometry_msgs/PoseStamped.h> | ||
#include <mujoco_ros_control/mujoco_default_robot_hw_sim.h> | ||
#include <nav_msgs/Odometry.h> | ||
|
||
namespace mujoco_ros_control | ||
{ | ||
class AerialRobotHWSim : public mujoco_ros_control::DefaultRobotHWSim | ||
{ | ||
public: | ||
AerialRobotHWSim() {}; | ||
~AerialRobotHWSim() {} | ||
|
||
bool init(const std::string& robot_namespace, | ||
ros::NodeHandle model_nh, | ||
mjModel* mujoco_model, | ||
mjData* mujoco_data | ||
) override; | ||
|
||
void read(const ros::Time& time, const ros::Duration& period) override; | ||
|
||
void write(const ros::Time& time, const ros::Duration& period) override; | ||
|
||
protected: | ||
hardware_interface::MujocoSpinalInterface spinal_interface_; | ||
|
||
std::vector<std::string> rotor_list_; | ||
ros::Publisher ground_truth_pub_; | ||
ros::Publisher mocap_pub_; | ||
double ground_truth_pub_rate_; | ||
double mocap_pub_rate_; | ||
double mocap_rot_noise_, mocap_pos_noise_; | ||
double ground_truth_pos_noise_, ground_truth_vel_noise_, ground_truth_rot_noise_, ground_truth_angular_noise_; | ||
double ground_truth_rot_drift_, ground_truth_vel_drift_, ground_truth_angular_drift_; | ||
double ground_truth_rot_drift_frequency_, ground_truth_vel_drift_frequency_, ground_truth_angular_drift_frequency_; | ||
double joint_state_pub_rate_ = 0.02; | ||
|
||
ros::Time last_mocap_time_; | ||
}; | ||
} |
29 changes: 29 additions & 0 deletions
29
aerial_robot_simulation/include/aerial_robot_simulation/mujoco/mujoco_attitude_controller.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,29 @@ | ||
#pragma once | ||
|
||
#include <ros/ros.h> | ||
#include <aerial_robot_estimation/state_estimation.h> | ||
#include <aerial_robot_simulation/mujoco/mujoco_spinal_interface.h> | ||
#include <flight_control/flight_control.h> | ||
#include <controller_interface/controller.h> | ||
#include <pluginlib/class_list_macros.h> | ||
|
||
namespace flight_controllers | ||
{ | ||
class MujocoAttitudeController : public controller_interface::Controller<hardware_interface::MujocoSpinalInterface> | ||
{ | ||
public: | ||
MujocoAttitudeController(); | ||
~MujocoAttitudeController() {} | ||
|
||
bool init(hardware_interface::MujocoSpinalInterface *robot, ros::NodeHandle &n); | ||
|
||
void starting(const ros::Time& time); | ||
void update(const ros::Time& time, const ros::Duration& period); | ||
|
||
private: | ||
hardware_interface::MujocoSpinalInterface* spinal_interface_; | ||
boost::shared_ptr<FlightControl> controller_core_; | ||
int motor_num_; | ||
|
||
}; | ||
} |
48 changes: 48 additions & 0 deletions
48
aerial_robot_simulation/include/aerial_robot_simulation/mujoco/mujoco_spinal_interface.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,48 @@ | ||
#pragma once | ||
|
||
#include <ros/ros.h> | ||
#include <hardware_interface/internal/hardware_resource_manager.h> | ||
#include <hardware_interface/hardware_interface.h> | ||
#include <aerial_robot_estimation/state_estimation.h> | ||
#include <state_estimate/state_estimate.h> | ||
#include <tf/LinearMath/Transform.h> | ||
#include <cassert> | ||
#include <limits> | ||
|
||
namespace hardware_interface | ||
{ | ||
class MujocoSpinalInterface : public HardwareInterface | ||
{ | ||
public: | ||
MujocoSpinalInterface(); | ||
bool init(ros::NodeHandle& nh, int motor_num); | ||
|
||
void setImuValue(double acc_x, double acc_y, double acc_z, double gyro_x, double gyro_y, double gyro_z); | ||
void setMagValue(double mag_x, double mag_y, double mag_z); | ||
void setTrueBaselinkOrientation(double q_x, double q_y, double q_z, double q_w); | ||
void setTrueBaselinkAngular(double w_x, double w_y, double w_z); | ||
|
||
tf::Vector3 getTrueBaselinkRPY(); | ||
inline tf::Vector3 getTrueBaselinkAngular() { return baselink_angular_;} | ||
tf::Vector3 getTrueCogRPY(); | ||
tf::Vector3 getTrueCogAngular(); | ||
|
||
void stateEstimate(); | ||
inline void onGround(bool flag) { on_ground_ = flag; } | ||
StateEstimate* getEstimatorPtr() {return &spinal_state_estimator_;} | ||
std::string getName() const{return "";} | ||
int getMotorNum() {return motor_num_;} | ||
double getForce(int index){return force_.at(index);} | ||
void setForce(int index, double force) {force_.at(index) = force;} | ||
|
||
private: | ||
/* attitude estimator */ | ||
bool on_ground_; | ||
|
||
int motor_num_; | ||
std::vector<double> force_; | ||
tf::Matrix3x3 baselink_rot_; | ||
tf::Vector3 baselink_angular_; | ||
StateEstimate spinal_state_estimator_; | ||
}; | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,20 @@ | ||
<?xml version="1.0" encoding="utf-8"?> | ||
<launch> | ||
<arg name="robot_ns" default="" /> | ||
<arg name="headless" default="false" /> | ||
<arg name="mujoco_model" default="" /> | ||
|
||
<!-- mujoco ros control --> | ||
<include file="$(find mujoco_ros_control)/launch/mujoco.launch" > | ||
<arg name="robot_ns" value="$(arg robot_ns)" /> | ||
<arg name="headless" value="$(arg headless)"/> | ||
<arg name="mujoco_model" value="$(arg mujoco_model)"/> | ||
</include> | ||
|
||
<!-- basic parameter --> | ||
<rosparam file="$(find aerial_robot_simulation)/config/Mujoco.yaml" command="load" ns="$(arg robot_ns)" /> | ||
|
||
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" | ||
output="screen" ns="$(arg robot_ns)" args="attitude_controller" /> | ||
|
||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
<library path="lib/libmujoco_aerial_robot_hw_sim"> | ||
<class | ||
name="mujoco_ros_control/AerialRobotHWSim" | ||
type="mujoco_ros_control::AerialRobotHWSim" | ||
base_class_type="mujoco_ros_control::RobotHWSim"> | ||
<description> | ||
simulation interface for aerial robot in MuJoCo. | ||
</description> | ||
</class> | ||
</library> |
Oops, something went wrong.