Drake
|
Namespaces | |
pick_and_place | |
Classes | |
class | IiwaAndWsgPlantWithStateEstimator |
A custom systems::Diagram composed of a systems::RigidBodyPlant, a systems::controllers::InverseDynamicsController, and a number of OracularStateEstimation systems. More... | |
class | IiwaCommandReceiver |
Handles lcmt_iiwa_command messages from a LcmSubscriberSystem. More... | |
class | IiwaCommandSender |
Creates and outputs lcmt_iiwa_command messages. More... | |
class | IiwaContactResultsToExternalTorque |
A translator class that converts the contact force field in systems::ContactResults to external joint torque for a set of specified model instances in RigidBodyTree. More... | |
class | IiwaStatusReceiver |
Handles lcmt_iiwa_status messages from a LcmSubscriberSystem. More... | |
class | IiwaStatusSender |
Creates and outputs lcmt_iiwa_status messages. More... | |
class | LcmPlanInterpolator |
class | OracularStateEstimation |
A System block that takes state vector and output a bot_core::robot_state_t message. More... | |
Functions | |
VectorX< double > | get_iiwa_max_joint_velocities () |
Returns the maximum joint velocities provided by Kuka. More... | |
template<typename T > | |
Matrix6< T > | ComputeLumpedGripperInertiaInEndEffectorFrame (const RigidBodyTree< T > &world_tree, int iiwa_instance, const std::string &end_effector_link_name, int wsg_instance) |
Computes the lumped inertia parameters of the gripper and the end effector link expressed in the end effector frame. More... | |
template Matrix6< double > | ComputeLumpedGripperInertiaInEndEffectorFrame (const RigidBodyTree< double > &, int, const std::string &, int) |
void | VerifyIiwaTree (const RigidBodyTree< double > &tree) |
Verifies that tree matches assumptions about joint indices. More... | |
void | CreateTreedFromFixedModelAtPose (const std::string &model_file_name, RigidBodyTreed *tree, const Vector3d &position, const Vector3d &orientation) |
void | SetPositionControlledIiwaGains (Eigen::VectorXd *Kp, Eigen::VectorXd *Ki, Eigen::VectorXd *Kd) |
Used to set the feedback gains for the simulated position controlled KUKA. More... | |
void | ApplyJointVelocityLimits (const MatrixX< double > &keyframes, std::vector< double > *time) |
Scales a plan so that no step exceeds the robot's maximum joint velocities. More... | |
robotlocomotion::robot_plan_t | EncodeKeyFrames (const RigidBodyTree< double > &robot, const std::vector< double > &time, const std::vector< int > &info, const MatrixX< double > &keyframes) |
Makes a robotlocomotion::robot_plan_t message. More... | |
robotlocomotion::robot_plan_t | EncodeKeyFrames (const std::vector< std::string > &joint_names, const std::vector< double > &time, const std::vector< int > &info, const MatrixX< double > &keyframes) |
Makes a robotlocomotion::robot_plan_t message. More... | |
void | CreateTreedFromFixedModelAtPose (const std::string &model_file_name, RigidBodyTreed *tree, const Eigen::Vector3d &position=Eigen::Vector3d::Zero(), const Eigen::Vector3d &orientation=Eigen::Vector3d::Zero()) |
Builds a RigidBodyTree at the specified and from the model specified by . More... | |
GTEST_TEST (IiwaLcmTest, IiwaCommandReceiverTest) | |
GTEST_TEST (IiwaLcmTest, IiwaCommandSenderTest) | |
GTEST_TEST (IiwaLcmTest, IiwaStatusReceiverTest) | |
GTEST_TEST (IiwaLcmTest, IiwaStatusSenderTest) | |
GTEST_TEST (IiwaLcmTest, IiwaContactResultsToExternalTorque) | |
Variables | |
constexpr int | kIiwaArmNumJoints = 7 |
const double | kIiwaLcmStatusPeriod = 0.005 |
static const int | kNumJoints = 7 |
void ApplyJointVelocityLimits | ( | const MatrixX< double > & | keyframes, |
std::vector< double > * | time | ||
) |
Scales a plan so that no step exceeds the robot's maximum joint velocities.
The number of columns in keyframes
must match the size of time
. Times must be in strictly increasing order.
Matrix6< T > ComputeLumpedGripperInertiaInEndEffectorFrame | ( | const RigidBodyTree< T > & | world_tree, |
int | iiwa_instance, | ||
const std::string & | end_effector_link_name, | ||
int | wsg_instance | ||
) |
Computes the lumped inertia parameters of the gripper and the end effector link expressed in the end effector frame.
world_tree | The RigidBodyTree that contains the arm and the gripper models. |
iiwa_instance | Identifier for the arm in world_tree . |
end_effector_link_name | Link name of the end effector. |
wsg_instance | Identifier for the gripper in world_tree . |
template Matrix6<double> drake::examples::kuka_iiwa_arm::ComputeLumpedGripperInertiaInEndEffectorFrame | ( | const RigidBodyTree< double > & | , |
int | , | ||
const std::string & | , | ||
int | |||
) |
void drake::examples::kuka_iiwa_arm::CreateTreedFromFixedModelAtPose | ( | const std::string & | model_file_name, |
RigidBodyTreed * | tree, | ||
const Eigen::Vector3d & | position = Eigen::Vector3d::Zero() , |
||
const Eigen::Vector3d & | orientation = Eigen::Vector3d::Zero() |
||
) |
Builds a RigidBodyTree at the specified and from the model specified by .
This method is a convinience wrapper over AddModelInstanceFromUrdfFile
.
void drake::examples::kuka_iiwa_arm::CreateTreedFromFixedModelAtPose | ( | const std::string & | model_file_name, |
RigidBodyTreed * | tree, | ||
const Vector3d & | position, | ||
const Vector3d & | orientation | ||
) |
robotlocomotion::robot_plan_t EncodeKeyFrames | ( | const RigidBodyTree< double > & | robot, |
const std::vector< double > & | time, | ||
const std::vector< int > & | info, | ||
const MatrixX< double > & | keyframes | ||
) |
Makes a robotlocomotion::robot_plan_t message.
The number of columns in keyframes
must match the size of time
. Times must be in strictly increasing order.
robotlocomotion::robot_plan_t EncodeKeyFrames | ( | const std::vector< std::string > & | joint_names, |
const std::vector< double > & | time, | ||
const std::vector< int > & | info, | ||
const MatrixX< double > & | keyframes | ||
) |
Makes a robotlocomotion::robot_plan_t message.
The number of rows in keyframes
must match the size of joint_names
. The number of columns in keyframes
must match the size of time
. Times must be in strictly increasing order.
Encode the q_sol returned for each timestep into the vector of robot states.
Returns the maximum joint velocities provided by Kuka.
drake::examples::kuka_iiwa_arm::GTEST_TEST | ( | IiwaLcmTest | , |
IiwaCommandReceiverTest | |||
) |
drake::examples::kuka_iiwa_arm::GTEST_TEST | ( | IiwaLcmTest | , |
IiwaCommandSenderTest | |||
) |
drake::examples::kuka_iiwa_arm::GTEST_TEST | ( | IiwaLcmTest | , |
IiwaStatusReceiverTest | |||
) |
drake::examples::kuka_iiwa_arm::GTEST_TEST | ( | IiwaLcmTest | , |
IiwaStatusSenderTest | |||
) |
drake::examples::kuka_iiwa_arm::GTEST_TEST | ( | IiwaLcmTest | , |
IiwaContactResultsToExternalTorque | |||
) |
void SetPositionControlledIiwaGains | ( | Eigen::VectorXd * | Kp, |
Eigen::VectorXd * | Ki, | ||
Eigen::VectorXd * | Kd | ||
) |
Used to set the feedback gains for the simulated position controlled KUKA.
void VerifyIiwaTree | ( | const RigidBodyTree< double > & | tree | ) |
Verifies that tree
matches assumptions about joint indices.
Aborts if the tree isn't as expected.
constexpr int kIiwaArmNumJoints = 7 |
const double kIiwaLcmStatusPeriod = 0.005 |
|
static |