Skip to content

Commit

Permalink
Change naming of variable
Browse files Browse the repository at this point in the history
  • Loading branch information
qiayuanl committed Dec 18, 2022
1 parent 5574223 commit 2f4a7e2
Show file tree
Hide file tree
Showing 11 changed files with 172 additions and 172 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -10,23 +10,23 @@ class ContactSensorHandle {
public:
ContactSensorHandle() = default;

ContactSensorHandle(const std::string& name, const bool* is_contact) : name_(name), is_contact_(is_contact) {
if (is_contact == nullptr) {
throw hardware_interface::HardwareInterfaceException("Cannot create handle '" + name + "'. is_contact pointer is null.");
ContactSensorHandle(const std::string& name, const bool* isContact) : name_(name), isContact_(isContact) {
if (isContact == nullptr) {
throw hardware_interface::HardwareInterfaceException("Cannot create handle '" + name + "'. isContact pointer is null.");
}
}

std::string getName() const { return name_; }

bool isContact() const {
assert(is_contact_);
return *is_contact_;
assert(isContact_);
return *isContact_;
}

private:
std::string name_;

const bool* is_contact_ = {nullptr};
const bool* isContact_ = {nullptr};
};

class ContactSensorInterface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,13 @@ class HybridJointHandle : public hardware_interface::JointStateHandle {
public:
HybridJointHandle() = default;

HybridJointHandle(const JointStateHandle& js, double* pos_des, double* vel_des, double* kp, double* kd, double* ff)
: JointStateHandle(js), pos_des_(pos_des), vel_des_(vel_des), kp_(kp), kd_(kd), ff_(ff) {
if (pos_des_ == nullptr) {
HybridJointHandle(const JointStateHandle& js, double* posDes, double* velDes, double* kp, double* kd, double* ff)
: JointStateHandle(js), posDes_(posDes), velDes_(velDes), kp_(kp), kd_(kd), ff_(ff) {
if (posDes_ == nullptr) {
throw hardware_interface::HardwareInterfaceException("Cannot create handle '" + js.getName() +
"'. Position desired data pointer is null.");
}
if (vel_des_ == nullptr) {
if (velDes_ == nullptr) {
throw hardware_interface::HardwareInterfaceException("Cannot create handle '" + js.getName() +
"'. Velocity desired data pointer is null.");
}
Expand All @@ -32,12 +32,12 @@ class HybridJointHandle : public hardware_interface::JointStateHandle {
}
}
void setPositionDesired(double cmd) {
assert(pos_des_);
*pos_des_ = cmd;
assert(posDes_);
*posDes_ = cmd;
}
void setVelocityDesired(double cmd) {
assert(vel_des_);
*vel_des_ = cmd;
assert(velDes_);
*velDes_ = cmd;
}
void setKp(double cmd) {
assert(kp_);
Expand All @@ -59,12 +59,12 @@ class HybridJointHandle : public hardware_interface::JointStateHandle {
setFeedforward(ff);
}
double getPositionDesired() {
assert(pos_des_);
return *pos_des_;
assert(posDes_);
return *posDes_;
}
double getVelocityDesired() {
assert(vel_des_);
return *vel_des_;
assert(velDes_);
return *velDes_;
}
double getKp() {
assert(kp_);
Expand All @@ -80,8 +80,8 @@ class HybridJointHandle : public hardware_interface::JointStateHandle {
}

private:
double* pos_des_ = {nullptr};
double* vel_des_ = {nullptr};
double* posDes_ = {nullptr};
double* velDes_ = {nullptr};
double* kp_ = {nullptr};
double* kd_ = {nullptr};
double* ff_ = {nullptr};
Expand Down
6 changes: 3 additions & 3 deletions legged_controllers/src/LeggedController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,13 +56,13 @@ bool LeggedController::init(hardware_interface::RobotHW* robot_hw, ros::NodeHand
}

auto* contactInterface = robot_hw->get<ContactSensorInterface>();
std::vector<ContactSensorHandle> contact_handles;
std::vector<ContactSensorHandle> contactHandles;
for (const auto& name : leggedInterface_->modelSettings().contactNames3DoF) {
contact_handles.push_back(contactInterface->getHandle(name));
contactHandles.push_back(contactInterface->getHandle(name));
}

// State estimation
setupStateEstimate(*leggedInterface_, hybridJointHandles_, contact_handles,
setupStateEstimate(*leggedInterface_, hybridJointHandles_, contactHandles,
robot_hw->get<hardware_interface::ImuSensorInterface>()->getHandle("unitree_imu"));

// Whole body control
Expand Down
6 changes: 3 additions & 3 deletions legged_controllers/src/TargetTrajectoriesPublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,18 +64,18 @@ TargetTrajectories goalToTargetTrajectories(const vector_t& goal, const SystemOb
return targetPoseToTargetTrajectories(targetPose, observation, targetReachingTime);
}

TargetTrajectories cmdVelToTargetTrajectories(const vector_t& cmd_vel, const SystemObservation& observation) {
TargetTrajectories cmdVelToTargetTrajectories(const vector_t& cmdVel, const SystemObservation& observation) {
const vector_t currentPose = observation.state.segment<6>(6);
const Eigen::Matrix<scalar_t, 3, 1> zyx = currentPose.tail(3);
vector_t cmdVelRot = getRotationMatrixFromZyxEulerAngles(zyx) * cmd_vel.head(3);
vector_t cmdVelRot = getRotationMatrixFromZyxEulerAngles(zyx) * cmdVel.head(3);

const scalar_t timeToTarget = TIME_TO_TARGET;
const vector_t targetPose = [&]() {
vector_t target(6);
target(0) = currentPose(0) + cmdVelRot(0) * timeToTarget;
target(1) = currentPose(1) + cmdVelRot(1) * timeToTarget;
target(2) = COM_HEIGHT;
target(3) = currentPose(3) + cmd_vel(3) * timeToTarget;
target(3) = currentPose(3) + cmdVel(3) * timeToTarget;
target(4) = 0;
target(5) = 0;
return target;
Expand Down
8 changes: 4 additions & 4 deletions legged_examples/legged_unitree/unitree_hw/src/unitree_hw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
int main(int argc, char** argv) {
ros::init(argc, argv, "unitree_hw");
ros::NodeHandle nh;
ros::NodeHandle robot_hw_nh("~");
ros::NodeHandle robotHwNh("~");

// Run the hardware interface node
// -------------------------------
Expand All @@ -54,14 +54,14 @@ int main(int argc, char** argv) {

try {
// Create the hardware interface specific to your robot
std::shared_ptr<legged::UnitreeHW> unitree_hw = std::make_shared<legged::UnitreeHW>();
std::shared_ptr<legged::UnitreeHW> unitreeHw = std::make_shared<legged::UnitreeHW>();
// Initialise the hardware interface:
// 1. retrieve configuration from rosparam
// 2. initialize the hardware and interface it with ros_control
unitree_hw->init(nh, robot_hw_nh);
unitreeHw->init(nh, robotHwNh);

// Start the control loop
legged::LeggedHWLoop control_loop(nh, unitree_hw);
legged::LeggedHWLoop controlLoop(nh, unitreeHw);

// Wait until shutdown signal received
ros::waitForShutdown();
Expand Down
4 changes: 2 additions & 2 deletions legged_gazebo/include/legged_gazebo/LeggedHWSim.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,8 @@ class LeggedHWSim : public gazebo_ros_control::DefaultRobotHWSim {
void writeSim(ros::Time time, ros::Duration period) override;

private:
void parseImu(XmlRpc::XmlRpcValue& imu_datas, const gazebo::physics::ModelPtr& parent_model);
void parseContacts(XmlRpc::XmlRpcValue& contact_names);
void parseImu(XmlRpc::XmlRpcValue& imuDatas, const gazebo::physics::ModelPtr& parentModel);
void parseContacts(XmlRpc::XmlRpcValue& contactNames);

HybridJointInterface hybridJointInterface_;
ContactSensorInterface contactSensorInterface_;
Expand Down
100 changes: 50 additions & 50 deletions legged_gazebo/src/LeggedHWSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,19 +53,19 @@ bool LeggedHWSim::initSim(const std::string& robot_namespace, ros::NodeHandle mo
}
// IMU interface
registerInterface(&imuSensorInterface_);
XmlRpc::XmlRpcValue xml_rpc_value;
if (!model_nh.getParam("gazebo/imus", xml_rpc_value)) {
XmlRpc::XmlRpcValue xmlRpcValue;
if (!model_nh.getParam("gazebo/imus", xmlRpcValue)) {
ROS_WARN("No imu specified");
} else {
parseImu(xml_rpc_value, parent_model);
parseImu(xmlRpcValue, parent_model);
}
if (!model_nh.getParam("gazebo/delay", delay_)) {
delay_ = 0.;
}
if (!model_nh.getParam("gazebo/contacts", xml_rpc_value)) {
if (!model_nh.getParam("gazebo/contacts", xmlRpcValue)) {
ROS_WARN("No contacts specified");
} else {
parseContacts(xml_rpc_value);
parseContacts(xmlRpcValue);
}

contactManager_ = parent_model->GetWorld()->Physics()->GetContactManager();
Expand Down Expand Up @@ -104,13 +104,13 @@ void LeggedHWSim::readSim(ros::Time time, ros::Duration period) {
if (static_cast<uint32_t>(contact->time.sec) != time.sec || static_cast<uint32_t>(contact->time.nsec) != (time - period).nsec) {
continue;
}
std::string link_name = contact->collision1->GetLink()->GetName();
if (name2contact_.find(link_name) != name2contact_.end()) {
name2contact_[link_name] = true;
std::string linkName = contact->collision1->GetLink()->GetName();
if (name2contact_.find(linkName) != name2contact_.end()) {
name2contact_[linkName] = true;
}
link_name = contact->collision2->GetLink()->GetName();
if (name2contact_.find(link_name) != name2contact_.end()) {
name2contact_[link_name] = true;
linkName = contact->collision2->GetLink()->GetName();
if (name2contact_.find(linkName) != name2contact_.end()) {
name2contact_[linkName] = true;
}
}

Expand Down Expand Up @@ -143,9 +143,9 @@ void LeggedHWSim::writeSim(ros::Time time, ros::Duration period) {
DefaultRobotHWSim::writeSim(time, period);
}

void LeggedHWSim::parseImu(XmlRpc::XmlRpcValue& imu_datas, const gazebo::physics::ModelPtr& parent_model) {
ROS_ASSERT(imu_datas.getType() == XmlRpc::XmlRpcValue::TypeStruct);
for (auto it = imu_datas.begin(); it != imu_datas.end(); ++it) {
void LeggedHWSim::parseImu(XmlRpc::XmlRpcValue& imuDatas, const gazebo::physics::ModelPtr& parentModel) {
ROS_ASSERT(imuDatas.getType() == XmlRpc::XmlRpcValue::TypeStruct);
for (auto it = imuDatas.begin(); it != imuDatas.end(); ++it) {
if (!it->second.hasMember("frame_id")) {
ROS_ERROR_STREAM("Imu " << it->first << " has no associated frame id.");
continue;
Expand All @@ -159,49 +159,49 @@ void LeggedHWSim::parseImu(XmlRpc::XmlRpcValue& imu_datas, const gazebo::physics
ROS_ERROR_STREAM("Imu " << it->first << " has no associated linear acceleration covariance.");
continue;
}
XmlRpc::XmlRpcValue ori_cov = imu_datas[it->first]["orientation_covariance_diagonal"];
ROS_ASSERT(ori_cov.getType() == XmlRpc::XmlRpcValue::TypeArray);
ROS_ASSERT(ori_cov.size() == 3);
for (int i = 0; i < ori_cov.size(); ++i) {
ROS_ASSERT(ori_cov[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
XmlRpc::XmlRpcValue oriCov = imuDatas[it->first]["orientation_covariance_diagonal"];
ROS_ASSERT(oriCov.getType() == XmlRpc::XmlRpcValue::TypeArray);
ROS_ASSERT(oriCov.size() == 3);
for (int i = 0; i < oriCov.size(); ++i) {
ROS_ASSERT(oriCov[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
}
XmlRpc::XmlRpcValue angular_cov = imu_datas[it->first]["angular_velocity_covariance"];
ROS_ASSERT(angular_cov.getType() == XmlRpc::XmlRpcValue::TypeArray);
ROS_ASSERT(angular_cov.size() == 3);
for (int i = 0; i < angular_cov.size(); ++i) {
ROS_ASSERT(angular_cov[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
XmlRpc::XmlRpcValue angularCov = imuDatas[it->first]["angular_velocity_covariance"];
ROS_ASSERT(angularCov.getType() == XmlRpc::XmlRpcValue::TypeArray);
ROS_ASSERT(angularCov.size() == 3);
for (int i = 0; i < angularCov.size(); ++i) {
ROS_ASSERT(angularCov[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
}
XmlRpc::XmlRpcValue linear_cov = imu_datas[it->first]["linear_acceleration_covariance"];
ROS_ASSERT(linear_cov.getType() == XmlRpc::XmlRpcValue::TypeArray);
ROS_ASSERT(linear_cov.size() == 3);
for (int i = 0; i < linear_cov.size(); ++i) {
ROS_ASSERT(linear_cov[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
XmlRpc::XmlRpcValue linearCov = imuDatas[it->first]["linear_acceleration_covariance"];
ROS_ASSERT(linearCov.getType() == XmlRpc::XmlRpcValue::TypeArray);
ROS_ASSERT(linearCov.size() == 3);
for (int i = 0; i < linearCov.size(); ++i) {
ROS_ASSERT(linearCov[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
}

std::string frame_id = imu_datas[it->first]["frame_id"];
gazebo::physics::LinkPtr link_ptr = parent_model->GetLink(frame_id);
ROS_ASSERT(link_ptr != nullptr);
imuDatas_.push_back((ImuData{.linkPrt_ = link_ptr,
.ori_ = {0., 0., 0., 0.},
.oriCov_ = {static_cast<double>(ori_cov[0]), 0., 0., 0., static_cast<double>(ori_cov[1]), 0., 0., 0.,
static_cast<double>(ori_cov[2])},
.angularVel_ = {0., 0., 0.},
.angularVelCov_ = {static_cast<double>(angular_cov[0]), 0., 0., 0., static_cast<double>(angular_cov[1]),
0., 0., 0., static_cast<double>(angular_cov[2])},
.linearAcc_ = {0., 0., 0.},
.linearAccCov_ = {static_cast<double>(linear_cov[0]), 0., 0., 0., static_cast<double>(linear_cov[1]), 0.,
0., 0., static_cast<double>(linear_cov[2])}}));
ImuData& imu_data = imuDatas_.back();
imuSensorInterface_.registerHandle(hardware_interface::ImuSensorHandle(it->first, frame_id, imu_data.ori_, imu_data.oriCov_,
imu_data.angularVel_, imu_data.angularVelCov_,
imu_data.linearAcc_, imu_data.linearAccCov_));
std::string frameId = imuDatas[it->first]["frame_id"];
gazebo::physics::LinkPtr linkPtr = parentModel->GetLink(frameId);
ROS_ASSERT(linkPtr != nullptr);
imuDatas_.push_back((ImuData{
.linkPrt_ = linkPtr,
.ori_ = {0., 0., 0., 0.},
.oriCov_ = {static_cast<double>(oriCov[0]), 0., 0., 0., static_cast<double>(oriCov[1]), 0., 0., 0., static_cast<double>(oriCov[2])},
.angularVel_ = {0., 0., 0.},
.angularVelCov_ = {static_cast<double>(angularCov[0]), 0., 0., 0., static_cast<double>(angularCov[1]), 0., 0., 0.,
static_cast<double>(angularCov[2])},
.linearAcc_ = {0., 0., 0.},
.linearAccCov_ = {static_cast<double>(linearCov[0]), 0., 0., 0., static_cast<double>(linearCov[1]), 0., 0., 0.,
static_cast<double>(linearCov[2])}}));
ImuData& imuData = imuDatas_.back();
imuSensorInterface_.registerHandle(hardware_interface::ImuSensorHandle(it->first, frameId, imuData.ori_, imuData.oriCov_,
imuData.angularVel_, imuData.angularVelCov_, imuData.linearAcc_,
imuData.linearAccCov_));
}
}

void LeggedHWSim::parseContacts(XmlRpc::XmlRpcValue& contact_names) {
ROS_ASSERT(contact_names.getType() == XmlRpc::XmlRpcValue::TypeArray);
for (int i = 0; i < contact_names.size(); ++i) { // NOLINT(modernize-loop-convert)
std::string name = contact_names[i];
void LeggedHWSim::parseContacts(XmlRpc::XmlRpcValue& contactNames) {
ROS_ASSERT(contactNames.getType() == XmlRpc::XmlRpcValue::TypeArray);
for (int i = 0; i < contactNames.size(); ++i) { // NOLINT(modernize-loop-convert)
std::string name = contactNames[i];
name2contact_.insert(std::make_pair(name, false));
contactSensorInterface_.registerHandle(ContactSensorHandle(name, &name2contact_[name]));
}
Expand Down
4 changes: 2 additions & 2 deletions legged_hw/include/legged_hw/LeggedHW.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,10 @@ class LeggedHW : public hardware_interface::RobotHW {
*
* Load urdf of robot from param server.
*
* @param root_nh Root node-handle of a ROS node
* @param rootNh Root node-handle of a ROS node
* @return True if successful.
*/
bool loadUrdf(ros::NodeHandle& root_nh);
bool loadUrdf(ros::NodeHandle& rootNh);
};

} // namespace legged
8 changes: 4 additions & 4 deletions legged_hw/src/LeggedHW.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,14 @@ bool LeggedHW::init(ros::NodeHandle& root_nh, ros::NodeHandle& /*robot_hw_nh*/)
return true;
}

bool LeggedHW::loadUrdf(ros::NodeHandle& root_nh) {
std::string urdf_string;
bool LeggedHW::loadUrdf(ros::NodeHandle& rootNh) {
std::string urdfString;
if (urdfModel_ == nullptr) {
urdfModel_ = std::make_shared<urdf::Model>();
}
// get the urdf param on param server
root_nh.getParam("legged_robot_description", urdf_string);
return !urdf_string.empty() && urdfModel_->initString(urdf_string);
rootNh.getParam("legged_robot_description", urdfString);
return !urdfString.empty() && urdfModel_->initString(urdfString);
}

} // namespace legged
Loading

0 comments on commit 2f4a7e2

Please sign in to comment.