<?xml version="1.0" encoding="UTF-8"?>
<rss version="2.0"
	xmlns:content="http://purl.org/rss/1.0/modules/content/"
	xmlns:wfw="http://wellformedweb.org/CommentAPI/"
	xmlns:dc="http://purl.org/dc/elements/1.1/"
	xmlns:atom="http://www.w3.org/2005/Atom"
	xmlns:sy="http://purl.org/rss/1.0/modules/syndication/"
	xmlns:slash="http://purl.org/rss/1.0/modules/slash/"
		xmlns:xhtml="http://www.w3.org/1999/xhtml"
>

<channel>
	<title>demura.net: ロボットの開発と教育 &#187; ODE</title>
	<atom:link href="http://demura.net/category/9ode/feed" rel="self" type="application/rss+xml" />
	<link>http://demura.net</link>
	<description>ロボット達のサッカーW杯RoboCup，つくばチャレンジ，物理計算エンジンＯＤＥと本サイトで開発している３次元描画ライブラリirrDrawStuffなどのロボット開発プラットフォームを開発者の視点で情報発信． なお，拙著ODE本では左動画のようなロボットシミュレータ作成法を学びます．まずは左動画をクリックして体験しよう！</description>
	<lastBuildDate>Sat, 31 Jul 2010 15:29:34 +0000</lastBuildDate>
	<generator>http://wordpress.org/?v=2.9.2</generator>
	<language>ja</language>
	<sy:updatePeriod>hourly</sy:updatePeriod>
	<sy:updateFrequency>1</sy:updateFrequency>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/category/9ode/feed" />
		<item>
		<title>一番簡単なODE自作プログラムのビルド法</title>
		<link>http://demura.net/9ode/7577.html</link>
		<comments>http://demura.net/9ode/7577.html#comments</comments>
		<pubDate>Wed, 28 Jul 2010 22:16:34 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>

		<guid isPermaLink="false">http://demura.net/?p=7577</guid>
		<description><![CDATA[premake4.luaへのファイル名追加に間違いがあったので記事を訂正しました。どうもすみません。 
くないさんから御質問があり、何らかの理由でビルドできない場合があります。コンピュータを持ってきてもらい詳細な手順など [...]]]></description>
			<content:encoded><![CDATA[<p><span style="color: #ff0000;">premake4.luaへのファイル名追加に間違いがあったので記事を訂正しました。どうもすみません。 </span></p>
<p>くないさんから御質問があり、何らかの理由でビルドできない場合があります。コンピュータを持ってきてもらい詳細な手順などを説明して頂ければすぐわかると思いますが、ブログへの書き込みだけではわからない場合も多いです。そこで、一番簡単なODE自作プログラムのビルド法を紹介します。ODEのデモプログラムをビルド実行できる方なら必ずうまくいくはずです。</p>
<p>その方法とは</p>
<p><span id="more-7577"></span>ODEデモプログラムと同じフォルダの中に御自分が作成したプログラムをコピーし、premake4.luaにそのファイル名を追加するという方法です。<span style="color: #ff0000;"><strong>ただし、ファイル名の先頭に</strong></span><span style="color: #ff0000;"><strong>必ずdemo_と付ける必要があります。</strong></span>以下具体的な手順を紹介します。</p>
<ul>
<li>まず、自分の作成したODEプログラムを<span style="color: #0000ff;"><strong>demo_myode.cpp</strong></span>とする。この方法では<strong><span style="color: #ff0000;">必ずdemo_を前に付けなければいけません。</span></strong></li>
<li>myode.cppをODEデモプログラムフォルダの中にコピーする。
<ul>
<li>例えばCドライブ直下にインストールした場合は次のフォルダにコピーする。
<ul>
<li>C:\ode-0.11.1\ode\demo</li>
</ul>
</li>
</ul>
</li>
<li>premake4.luaの13行目にdemo_myode.cppからdemo_と.cppを取ったファイル名<span style="color: #0000ff;"><strong>&#8221; myode&#8221;, </strong></span>を挿入し保存する。これにより、14行目が&#8221;boxstack&#8221;, となる。</li>
<pre class="brush:cpp">----------------------------------------------------------------------
-- Premake4 configuration script for OpenDE
-- Contributed by Jason Perkins
-- For more information on Premake: http://industriousone.com/premake
----------------------------------------------------------------------

----------------------------------------------------------------------
-- Demo list: add/remove demos from here and the rest of the build
-- should just work.
----------------------------------------------------------------------

  local demos = {
	"myode",
    "boxstack",
    "buggy",
    "cards",</pre>
<li>後はODEのビルド法と同じです。premakeの設定ファイルpremake4.luaを書き換えたのでもう一度premake4コマンドを実行する必要があります。以下のページを参考にしてビルドしてください。
<ul>
<li><a href="http://demura.net/9ode/3864.html">Windows+Visual C++はこのページ</a></li>
<li><a href="http://demura.net/9ode/3850.html">Windows+Codeblocksはこのページ</a>
<ul>
<li>コマンドプロンプトを起動して以下のコマンドをカットアンドペーストする。</li>
<li>cd   c:\ode-0.11.1\build</li>
<li><code> premake4  --with-demos  --cc=gcc  --os=windows  codeblocks </code></li>
<li>成功するとcodeblocksというフォルダがbuildフォルダの中に生成される。そのなかに、demo_myode.cbpというcodeblocks用のプロジェクトファイルが生成される。</li>
<li>demo_myode.cbpをcodeblocksで開きビルドする。その場合、ビルドターゲットをDebugDoubleLibを選ぶ（demura.netのODEインストール法に従った場合）。違うターゲットを選ぶとライブラリがないと怒られビルドできない。</li>
<li>終わり。お疲れ様。</li>
</ul>
</li>
<li><a href="http://demura.net/9ode/3902.html">Linux+Codeblocksはこのページ</a></li>
</ul>
</li>
<li>以上です。</li>
</ul>
<p style="text-align: right;">でむ</p>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=7577&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/7577.html/feed</wfw:commentRss>
		<slash:comments>4</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/7577.html" />
	</item>
		<item>
		<title>ODEで学ぶC言語２ [Step6: まとめ]</title>
		<link>http://demura.net/9ode/7582.html</link>
		<comments>http://demura.net/9ode/7582.html#comments</comments>
		<pubDate>Mon, 26 Jul 2010 14:07:18 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>

		<guid isPermaLink="false">http://demura.net/?p=7582</guid>
		<description><![CDATA[

ODEで学ぶC言語２のStep6です．今回で最終回となります．ODEのジョイントの生成法と簡単な制御のサンプルプログラムを学びましょう．
ジョイントは我々の周りでは、折畳み携帯のヒンジやドアの蝶番に相当します。小難し [...]]]></description>
			<content:encoded><![CDATA[<p><br class="spacer_" /></p>
<div id="attachment_7586" class="wp-caption aligncenter" style="width: 520px"><a href="http://demura.net/wordpress/wp-content/uploads/2010/07/step6.jpg"><img src="http://demura.net/wordpress/wp-content/uploads/2010/07/step6.jpg" title="step6" width="510" height="419" class="size-full wp-image-7586" /></a><p class="wp-caption-text">STEP6: 玉突きロボット</p></div>
<p><br class="spacer_" /></p>
<p>ODEで学ぶC言語２のStep6です．今回で最終回となります．ODEのジョイントの生成法と簡単な制御のサンプルプログラムを学びましょう．</p>
<p>ジョイントは我々の周りでは、折畳み携帯のヒンジやドアの蝶番に相当します。小難しくいうと、２つのボディの位置や姿勢をある一定の関係に保つ拘束がジョイントとなのです。ODEではジョイントと拘束を同じ意味で使っています。</p>
<p>ODEのジョイント（関節）は２つのボディ(剛体，body)をつなげるものです。１つのジョイントで３個以上のボディをつなげることはできませんし，１個のボディだけをつなげることもできません．必ず２個のボディを１つのジョイントでつなげなければなりません．</p>
<p><span id="more-7582"></span></p>
<p>また，ODEのジョイントは摩擦がありませんし，可動域を設定しないと+dInfinity(+無限大)から-dInfinity（-無限大）まで回転または移動します．角度は[rad]です．</p>
<p><br class="spacer_" /></p>
<ul>
<li><strong>ジョイントの使い方</strong></li>
</ul>
<ol>
<li><span style="color: #cc0000;"><strong>***ジョイントの生成　　　　　　dmJointCreate***()</strong></span></li>
<li><span style="color: #cc0000;"><strong>***ジョイントとボディの結合　 dJointAttach(dJointID, dBodyID, dBodyID)</strong></span></li>
<li><span style="color: #cc0000;"><strong>***ジョイントの中心点を設定　dJointSet***Anchor()</strong></span></li>
<li><span style="color: #cc0000;"><strong>***ジョイントの回転軸を設定　dJointSet***Axis()</strong></span></li>
</ol>
<p>上で***にはジョイントのタイプが入ります。タイプにはHinge(ヒンジ）、Slider(スライダー)があります。サンプルプログラムではヒンジジョイントと直動式のスライダージョイントを使います．</p>
<ul>
<li><strong>ジョイントのパラメータ設定</strong></li>
</ul>
<ol>
<li><strong>可動域の設定</strong><br />
<strong><span style="color: #ff0000;">dJointSetHingeParam(dJointID, dParamLoStop, 可動域の下限）;</span></strong><br />
<strong><span style="color: #ff0000;">dJointSetHingeParam(dJointID, dParamHiStop, 可動域の上限）;</span></strong></li>
<li><strong>目標角速度とそれを実現するための最大トルクの設定<br />
<span style="color: #ff0000;">dJointSetHingeParam(dJointID, dParamVel,  目標角速度）;</span></strong><strong><br />
<span style="color: #ff0000;">dJointSetHingeParam(dJointID, dParamFMax, 最大トルク）;</span></strong></li>
</ol>
<p>パラメータとしては、関節可動域の下限を示すdParamLoStop、上限を示すdParamHiStop、角速度（ヒンジジョイント）または速度(直動式関節）を示すdParamVel、最大トルクを示すdParaFMaxなどがあります。なお、ODEでは関節にモータが標準で組み込まれているので、dParamVelやdParaFMaxを指定すると関節が動きます。</p>
<p><strong>ソースコード</strong><br />
少し長くなりますが，ソースコードを掲載します．このコードは今まで習った，キー操作関数，シミュレーションの再スタート，ボディへ力を加えるなどのほかに，ジョイントの生成と制御法など簡単なゲームやシミュレータを作るために必要なことは一通り入っています．</p>
<pre class="brush:cpp">/* step6　*/

#define START_X 0.0
#define START_Y 0.0
#define START_Z 0.1

dmObject torso, leg&#91;2&#93;, ball;
static int STEPS = 0;      // シミュレーションのステップ数
double S_LENGTH  = 0.0;    // スライダー長
double H_ANGLE   = 0;      //ヒンジの角度

// ロボットの生成
void createMonoBot()
{
    int i;
    double l_leg = 0.75; // 長さ
    double m_leg = 1.0;  // 質量
    double r_leg&#91;2&#93; = {0.05, 0.03}; // 半径
    double m_torso = 100.0; // 胴体の質量
    double r_torso = 0.25;  // 胴体の半径
    double l_torso = 0.2;   // 胴体の高さ
    double r_ball = 0.11;   // ボールの半径
    double m_ball = 0.5;    // ボールの質量
    double p_ball&#91;3&#93; = {START_X, START_Y+2*l_leg+0.1, START_Z}; // ボールの位置
    double p_torso&#91;3&#93; = {START_X, START_Y, START_Z};  // 位置
    double p_leg&#91;2&#93;&#91;3&#93; = {{START_X, START_Y+0.5*l_leg, START_Z},
        {START_X, START_Y+l_leg, START_Z}
    };
    double p_anchor&#91;3&#93; = {START_X, START_Y, START_Z};
    double R&#91;12&#93;;   // 回転行列

    static double  red&#91;3&#93; = {1.0, 0.0, 0.0}; // 色
    static double  color_leg&#91;2&#93;&#91;3&#93; = {{0.0, 0.0, 1.0},{1.3, 1.3, 1.3}};

    dRSetIdentity(R);  //回転行列を単位行列で初期化
    dmCreateSphere(&amp;ball, p_ball,R,m_ball, r_ball, red); // ボールの生成
    dmCreateCylinder(&amp;torso,p_torso,R,m_torso,r_torso,l_torso,red); // 胴体の生成

    dRFromAxisAndAngle(R, 1, 0, 0, M_PI/2);
    for (i = 0; i &#60; 2; i++)
    {
        dmCreateCapsule(&amp;leg&#91;i&#93;,p_leg&#91;i&#93;,R,m_leg,r_leg&#91;i&#93;,l_leg,color_leg&#91;i&#93;); // 脚の生成
    }

    // ヒンジジョイント
    leg&#91;0&#93;.joint = dmJointCreateHinge();
    dJointAttach(leg&#91;0&#93;.joint, torso.body,leg&#91;0&#93;.body);
    dJointSetHingeAnchor(leg&#91;0&#93;.joint, p_anchor&#91;0&#93;,p_anchor&#91;1&#93;,p_anchor&#91;2&#93;);
    dJointSetHingeAxis(leg&#91;0&#93;.joint, 0, 0, 1);

    // スライダージョイント
    leg&#91;1&#93;.joint = dmJointCreateSlider();
    dJointAttach(leg&#91;1&#93;.joint, leg&#91;0&#93;.body,leg&#91;1&#93;.body);
    dJointSetSliderAxis(leg&#91;1&#93;.joint, 0, 1, 0);
    dJointSetSliderParam(leg&#91;1&#93;.joint, dParamLoStop, -0.25);
    dJointSetSliderParam(leg&#91;1&#93;.joint, dParamHiStop,  0.25);
}

// ヒンジジョイントの制御
static void controlHinge(dReal target)
{
    static dReal kp = 10.0, fmax = 1000;

    dReal tmp   = dJointGetHingeAngle(leg&#91;0&#93;.joint);
    dReal diff  = target - tmp;
    if (diff &#62;=   M_PI) diff -= 2.0 * M_PI; // diffが2πより小さく
    if (diff &#60;= - M_PI) diff += 2.0 * M_PI; // diffが-2πより大きく
    dReal u     = kp * diff;

    dJointSetHingeParam(leg&#91;0&#93;.joint, dParamVel,  u);
    dJointSetHingeParam(leg&#91;0&#93;.joint, dParamFMax, fmax);
}

// スライダの制御 プログラム2.4
static void controlSlider(dReal target)
{
    static dReal kp   = 25.0;                       // 比例定数
    static dReal fmax = 1000;                        // 最大力&#91;N&#93;
    double tmp, u;

    tmp  = dJointGetSliderPosition(leg&#91;1&#93;.joint);  // スライダの現在位置
    u    = kp * (target - tmp);                    // 残差
    dJointSetSliderParam(leg&#91;1&#93;.joint, dParamVel,  u);
    dJointSetSliderParam(leg&#91;1&#93;.joint, dParamFMax, fmax);
}

// シミュレーションのリセット
static void resetSim()
{
    STEPS    = 0;      // ステップ数の初期化
    H_ANGLE  = 0.0;    // ヒンジ角度の初期化
    S_LENGTH = 0.0;

    if (STEPS != 0) dmClose(); // シミュレーションの終了

    dmInit();  // シミュレーションの初期化
    createMonoBot();
}

// キー操作
void command(int cmd)
{
    switch (cmd)
    {
    case 'j':
        S_LENGTH =   0.25;
        break;
    case 'l':
        S_LENGTH = - 0.25;
        break;
    case 'i':
        H_ANGLE +=   0.25;
        if (H_ANGLE  &#62;   M_PI) H_ANGLE  =  -M_PI;
        break;
    case 'm':
        H_ANGLE -=   0.25;
        if (H_ANGLE  &#60;  -M_PI) H_ANGLE  =   M_PI;
        break;
    case 'r':
        resetSim();
        break;
    case 'a':
        dBodyAddForce(torso.body, 0, -500, 0);
        break;
    case 'w':
        dBodyAddForce(torso.body, -500, 0, 0);
        break;
    case 'd':
        dBodyAddForce(torso.body, 0,  500, 0);
        break;
    case 'x':
        dBodyAddForce(torso.body,  500, 0, 0);
        break;
    case 's':
        dBodySetLinearVel(torso.body,  0, 0, 0);
        dBodySetAngularVel(torso.body, 0, 0, 0);
        break;
    default :
        printf("key missed \n");
        break;
    }
}

void simLoop(int pause)           /***  シミュレーションループ　***/
{
    int i;
    int s = 1000;                   // 跳躍する周期(ステップ)

    if (!pause)
    {
        printf("STEPS=%d \n",STEPS++); //  ステップ数

        // スライダーの伸縮
        //if ((0 &#60;= (STEPS%s)) &amp;&amp; ((STEPS%s) &#60;= 10)) S_LENGTH = 0.6;
        //else if ((11 &#60;= (STEPS%s)) &amp;&amp; ((STEPS%s) &#60;= 15)) S_LENGTH = 0.0;

        controlSlider(S_LENGTH); // スライダージョイントの制御
        controlHinge(H_ANGLE);   // ヒンジジョイントの制御

        dmSimStep(); // シミュレーションを１ステップ進める
    }

    dmDraw(&amp;ball); // ボールの描画
    // ロボットの描画
    dmDraw(&amp;torso);   // 胴体の描画
    for (i = 0; i &#60; 2; i++)dmDraw(&amp;leg&#91;i&#93;); //脚の描画
    STEPS++;
}

int main()         /*** main関数 ***/
{
    dmInit(); // ODEの初期化
    resetSim();   // ロボットの生成
    dmLoop(800, 600, simLoop, command);  // シミュレーションループ ウインドウの幅，高
    dmClose();          // ODEの終了
    return 0;
}</pre>
<p><strong>ホームワーク</strong></p>
<ul>
<li><a href="http://demura.net/wordpress/wp-content/uploads/2010/07/step6-100726.zip">step6-100726.zip</a>をダウンロードして実行してみましょう．</li>
<li>サンプルプログラムを改良してビリヤードをプレイするロボットを作りましょう．</li>
</ul>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=7582&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/7582.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/7582.html" />
	</item>
		<item>
		<title>ODEで学ぶC言語２ [STEP5: 構造体]</title>
		<link>http://demura.net/9ode/7524.html</link>
		<comments>http://demura.net/9ode/7524.html#comments</comments>
		<pubDate>Mon, 19 Jul 2010 22:03:53 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>

		<guid isPermaLink="false">http://demura.net/?p=7524</guid>
		<description><![CDATA[ODEで学ぶC言語2のStep5です．今回は構造体と物体へ力やトルクを加える方法，さらにシミュレーションのリセット法などを学びます．構造体の概要については既にわかっているものとし，サンプルコードを示すことにより具体的な使 [...]]]></description>
			<content:encoded><![CDATA[<div id="attachment_7525" class="wp-caption aligncenter" style="width: 622px"><a href="http://demura.net/wordpress/wp-content/uploads/2010/07/domino.jpg"><img src="http://demura.net/wordpress/wp-content/uploads/2010/07/domino.jpg" alt="domino" title="domino" width="612" height="450" class="size-full wp-image-7525" /></a><p class="wp-caption-text">Step5サンプルプログラム：ドミノ倒し</p></div>
<p>ODEで学ぶC言語2のStep5です．今回は構造体と物体へ力やトルクを加える方法，さらにシミュレーションのリセット法などを学びます．構造体の概要については既にわかっているものとし，サンプルコードを示すことにより具体的な使い方を学びます．</p>
<p><span id="more-7524"></span></p>
<p><strong>○　構造体</strong></p>
<p>配列では同じ型しかまとめることができませんでしたが，構造体では違う型をまとめて扱うことができるのでシミュレーションなど物体に多くの属性がある場合に便利です．このサンプルプログラムでは物体をdmObjectという構造体で次のように表しています．dm5.hの１６行目に定義しています．今回の例はドミノ倒しなので，この構造体を元にドミノを21個生成しています．</p>
<pre class="brush:cpp;">typedef struct{
    dBodyID body; // ボディのID
    dGeomID geom; // ジオメトリのID
    const double *p; // x, y, z　&#91;m&#93;
    const double *R;   // 回転行列 要素数4x3
    double m; // 質量 &#91;kg&#93;
    double r,l; // 半径 &#91;m&#93;, 長さ &#91;m&#93;
    const double *side; // サイズ　x,y,z
    const double *color; // 色 r,g,b
} dmObject;</pre>
<p>○<strong> 姿勢の変更</strong></p>
<p>物体の姿勢を変更するためには次のAPIを使い回転行列Rの値を変更します．ここで，Rは回転行列が格納されている配列へのポインタ，ax, ay, axは回転軸ベクトル．angleは回転角度となります．なお，dだけで始まるAPIはODEのAPIです．</p>
<ul>
<li><strong>dRFromAxisAndAngle(double　R[12], double  ax, doulbe  ay, double  az, double angle);</strong></li>
</ul>
<p><strong>○　力，トルクの加え方</strong></p>
<ul>
<li><strong>void dmAddForce(dmObject *obj, double fx, double fy, double fz)</strong>
<ul>
<li>物体objの重心に力(fx,fy,fz)を加える</li>
</ul>
</li>
<li><strong>void dmAddTorque(dmObject *obj, double fx, double fy, double fz)</strong>
<ul>
<li>物体objの重心にトルク(fx, fy, fz)を加える．fx，ｆｙ，ｆｚはそれぞれx, y, z軸まわりのトルク</li>
</ul>
</li>
</ul>
<p>○　<strong>高速なシミュレーション</strong></p>
<p>前回のサンプルではシミュレーションのステップ関数としてdmSimStep()を使いましたが，ここではより高速なdmSimQuickStep()を使います．ただし，dmSimStep()と比較して精度が悪くなります．</p>
<p><strong>○　シミュレーションのリセット</strong></p>
<p>rまたはRキーを押すと，resetSim関数が呼ばれてシミュレーションがリセットされます．resetSimの中身はシミュレーションループが１回以上呼び出されたときにdmInit関数を呼び出して初期化し，ドミノを再度生成しています．</p>
<p><strong>○　ソースコード</strong></p>
<pre class="brush:cpp;">/* step5 ドミノ倒し 　*/
#include "dm5.h"
#define DOMINO_NUM  21

static int STEPS = 0;   // シミュレーションのステップ数
double red&#91;3&#93; = {1.3, 0.0, 0.0}; // 赤色
dmObject domino&#91;DOMINO_NUM&#93;; // ドミノ

void simLoop(int pause)           /***  シミュレーションループ　***/
{

    int i;
    double x = 5.0, y = 0, z = 1; // カメラの位置&#91;m&#93;
    double yaw = -180, pitch = 0, roll = 0; // カメラの姿勢　ヨー，ピッチ，ロール角&#91;°&#93;

    if (STEPS == 0) dmSetCamera(x,y,z,yaw,pitch,roll); // カメラの設定

    dmSimQuickStep(); // シミュレーションを１ステップ進める(高速版)

    for (i = 0; i &#60; DOMINO_NUM; i++)
    {
        dmDraw(&amp;domino&#91;i&#93;); //　壁の描画
    }
    STEPS++;
}

void resetSim(int n)
{
    double m = 0.1; // 質量
    double side&#91;3&#93; = {0.2, 0.05, 0.5}; // サイズ
    double R&#91;12&#93; = {1,0,0,0, 0,1,0,0, 0,0,1,0}; // 姿勢
    double p&#91;DOMINO_NUM&#93;&#91;3&#93;;  // 位置

    int i;

    // シミュレーションの終了
    if (STEPS != 0)
    {
        dmClose();
    }

    dmInit(); // 初期化

    // ドミノの生成
    for (i = 0; i &#60; DOMINO_NUM; i++)
    {
        p&#91;i&#93;&#91;2&#93; = 0.25; // ドミノ重心のz座標
        switch (n)
        {
        case 0:
            p&#91;i&#93;&#91;0&#93; = 0;             // ドミノ重心のx座標
            p&#91;i&#93;&#91;1&#93; = 0.3 * i -3.0;  // ドミノ重心のy座標
            break;
        case 1:
            p&#91;i&#93;&#91;0&#93; = 0.3 * i -3.0;
            p&#91;i&#93;&#91;1&#93; = p&#91;i&#93;&#91;0&#93;;
            // z軸周りにπ/4回転させた姿勢
            dRFromAxisAndAngle(R, 0, 0, 1, - M_PI/4);
            break;
        default:
            printf("Bad number \n");
            break;
        }
        dmCreateBox(&amp;domino&#91;i&#93;, p&#91;i&#93;, R, m, side, red);
    }
}

void command(int cmd)
{
    switch (cmd)
    {
    case '1':
        resetSim(1);
        break;
    case 'r':
    case 'R':
        resetSim(0);
        break;
    case 'f':
    case 'F':
    {
        double fx = -1.0, fy = 0.0, fz = 0.0;
        dmAddTorque(&amp;domino&#91;0&#93;, fx, fy, fz); // x,y,z軸まわりにfx,fy,fzのトルクを付加
        break;
    }
    default:
        printf("Input r, R, f, F key \n");
        break;
    }
}

/*** main関数 ***/
int main()
{
    resetSim(0); // シミュレーションのリセット
    dmLoop(800, 600, simLoop, command);  // ウインドウの幅，高, ループ関数，コマンド関数
    dmClose(); // 終了

    return 0;
}</pre>
<p><strong>ホームワーク</strong></p>
<ol>
<li>サンプルコード<a href="http://demura.net/wordpress/wp-content/uploads/2010/07/step5-100720.zip">step5-100720.zip</a>をここからダウンロードして実行しよう．</li>
<li> ドミノを X状に配置して，ドミノ倒しをしなさい.  解答例<a href="http://demura.net/wordpress/wp-content/uploads/2010/07/step5b-100726.zip">step5b-100726.zip</a></li>
<li>ドミノを半径２ｍの円上に配置して，ドミノ倒しをしなさい</li>
<li>上の配置でドミノ倒しが無限に続くように，ドミノがひとりでに起き上がるようにしなさい．</li>
</ol>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=7524&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/7524.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/7524.html" />
	</item>
		<item>
		<title>ODEで学ぶC言語2　[Step4: 関数]</title>
		<link>http://demura.net/9ode/7469.html</link>
		<comments>http://demura.net/9ode/7469.html#comments</comments>
		<pubDate>Thu, 08 Jul 2010 12:11:36 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>

		<guid isPermaLink="false">http://demura.net/?p=7469</guid>
		<description><![CDATA[ODEで学ぶC言語のStep4です．今回は私がODEのAPIを元に作成した関数を使い，赤い球を落下させるプログラムを説明します．
今までのプログラムでは描画だけでしたが，今回からシミュレーションやゲームを作るために必要な [...]]]></description>
			<content:encoded><![CDATA[<div id="attachment_7485" class="wp-caption aligncenter" style="width: 673px"><a href="http://demura.net/wordpress/wp-content/uploads/2010/07/step4.jpg"><img src="http://demura.net/wordpress/wp-content/uploads/2010/07/step4.jpg" alt="落下する赤い球" title="step4" width="663" height="532" class="size-full wp-image-7485" /></a><p class="wp-caption-text">落下する赤い球</p></div>
<p>ODEで学ぶC言語のStep4です．今回は私がODEのAPIを元に作成した関数を使い，赤い球を落下させるプログラムを説明します．</p>
<div id="_mcePaste">今までのプログラムでは描画だけでしたが，今回からシミュレーションやゲームを作るために必要な動力学計算や衝突検出計算も含んでいます．サンプルプログラムとしては，物理シミュレーションで最も簡単な物体の落下を取り上げます．C言語などのプログラミングの教科書では初めの例題はHello Worldを表示する例が定番です。ここではHello Worldの物理シミュレーション版を紹介します．</div>
<div><span id="more-7469"></span></div>
<div>
<p><span style="font-family: 'MS PGothic'; line-height: 18px; font-size: 14px;"> </span></p>
<ul>
<li><strong>API</strong>
<p style="padding-left: 25px;">ここでは簡単にするためにODEのAPIを元に，超簡単なAPIを作成しました．ただし、ODEのAPIのように細かいことはできません。</p>
<ul>
<li><strong>void dmInit()；<br />
</strong>シミュレーションを初期化します．</li>
<li><strong>void dmCreateSphere(dmObject *obj, double p[3], double R[12], double m, double r, double color[3]);<br />
</strong>球を作成します．引数のp[3]は位置(x,y,z)[m]，R[12]は姿勢（回転行列）, mは質量[kg]，rは半径[m]，color[3]は色(赤，緑，青各成分、値は0以上1以下）です．</li>
<li><strong>void dmSimStep();</strong><br />
シミュレーションを１ステップ進めます．</li>
<li><strong>dmDraw(MyObject obj);<br />
<span style="font-weight: normal;">引数のオブジェクトobjを描画する．<br />
</span> </strong></li>
</ul>
</li>
<li><strong>ソースコード</strong>
<ul>次に、詳しいコメントのついたソースコードを以下に示します。main関数から読んでください。</p>
<pre class="brush:cpp">/* step4 リンゴ（林檎）の落下 　*/
#include "dm4.h"

dmObject apple;  // リンゴ

void simLoop(int pause)           /***  シミュレーションループ　***/
{
    dmSimStep(); // シミュレーションを１ステップ進める
    dmDraw(apple);   // リンゴの描画
}

int main()   /*** main関数 ***/
{
    double p1[3] = {0.0, 0.0, 2.0}; // 位置 [m]
    double R[12] = {1,0,0,0, 0,1,0,0, 0,0,1,0}; // 姿勢（回転行列）

    double red[3]    = {1.0, 0.0, 0.0};　// 赤色
    double r = 0.2, m = 1.0;  // 半径[m],質量[kg]

    dmInit(); // 初期化
    dmCreateSphere(&amp;apple, p1, R, m, r, red); // 球の作成
    dmLoop(800, 600, simLoop, NULL);  // ウインドウの幅，高, ループ関数，コマンド関数
    dmClose(); // 終了処理

    return 0;
}</pre>
<li>これは赤い玉の自由落下のプログラムです。まず、dmInit()でシミュレーションを初期化します。</li>
<li>次に物体を作ります．球を作るAPIはdmCreateSphere()です．</li>
<li>物体の生成が終わったら、次はシミュレーションを１ステップ進めます。dmLoop()の中身はwhileループになっていて、繰り返しsimLoop関数が呼び出しています。dmLoop()の一番最後の引数がNULLになっているのは、このサンプルプログラムではキー操作可能なcommand関数がないからです。前回の例のようにcommand関数がある場合はNULLの代わりにcommandを入れてください。</li>
<li>お次は物体の描画です．dmDraw(apple)で落下する球を表示しています。dmDraw()の引数は表示したい物体をいれてください。</li>
<li>最後にシミュレーションをdmClose()で終了します．なお、小文字のdmで始まる関数は私がこの講義用にODEのAPI(application interface)を元に作成したものです．</li>
</ul>
</li>
<li><strong>ホームワーク </strong>
<ol>
<li><a href="http://demura.net/wordpress/wp-content/uploads/2010/07/step4-100709.zip">step4-100709.zip</a>をダウンロードして実行しよう！</li>
<li>次のAPIを使い青いボックスを位置p[3]={0.0, 1.0, 2.0}に作成し，落下させるプログラムを作ってください．
<ul>
<li>void dmCreateBox(dmObject *obj, double p[3], double R[12], double m, double side[3],  double color[3]);</li>
<li>物体 obj, 位置　p[3], 　姿勢（回転行列）R[12],  質量　m, サイズ(x,y,z) side[3], 色　color[3]</li>
<li>なお、回転行列は3&#215;3行列ですが、ODEでは高速化のために3&#215;4行列として各行の最後に0を追加しています。</li>
</ul>
</li>
<li>今度は緑色の円柱を位置(0.0, -1.0, 2.0)に作成し，落下させなさい．
<ul>
<li>void dmCreateCylinder(dmObject *obj, double p[3], double R[12], double m, double r, double l, double color[3]);</li>
<li>物体 obj, 位置　p[3], 　姿勢　R[12],  サイズ sides[3], 半径 r, 長さ l,　質量　m, 色　color[3]</li>
</ul>
</li>
<li>最後に，黄色のカプセルを位置(-1, 0, 2)に作成し，落下させなさい．
<ul>
<li>dBodyID  dmCreateCapsule(dmObject *obj, double p[3], double R[12], double m, double r, double l, double color[3]);</li>
<li>物体 obj, 位置　p[3], 　姿勢　R[12],  サイズ sides[3], 半径 r, 長さ l,　質量　m, 色　color[3]</li>
</ul>
</li>
</ol>
</li>
</ul>
<p><br class="spacer_" /></p>
</div>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=7469&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/7469.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/7469.html" />
	</item>
		<item>
		<title>ODEで学ぶC言語２ [Step3：switch文とキー処理関数]</title>
		<link>http://demura.net/9ode/7421.html</link>
		<comments>http://demura.net/9ode/7421.html#comments</comments>
		<pubDate>Thu, 01 Jul 2010 22:54:50 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>

		<guid isPermaLink="false">http://demura.net/?p=7421</guid>
		<description><![CDATA[Step2でfor文を使った繰り返しを練習したので，ここではswitch文を使ったキー処理の方法を学びます．
ゲームなどではキーボードでレーザービームを発射したり，車を操縦しますね．ここでも，キーボードからのキー入力を処 [...]]]></description>
			<content:encoded><![CDATA[<div id="attachment_7432" class="wp-caption aligncenter" style="width: 460px"><a href="http://demura.net/wordpress/wp-content/uploads/2010/07/step3a.jpg"><img src="http://demura.net/wordpress/wp-content/uploads/2010/07/step3a.jpg" alt="step3サンプルプログラムの実行画面" title="step3a" width="450" height="384" class="size-full wp-image-7432" /></a><p class="wp-caption-text">step3サンプルプログラムの実行画面</p></div>
<p>Step2でfor文を使った繰り返しを練習したので，ここではswitch文を使ったキー処理の方法を学びます．</p>
<p>ゲームなどではキーボードでレーザービームを発射したり，車を操縦しますね．ここでも，キーボードからのキー入力を処理する方法を学びます．</p>
<p><span id="more-7421"></span></p>
<p><strong>switch文とキー処理</strong></p>
<p>新しく登場したのが11行目のcommand関数です．これは，キーボードからのキー入力を引数cmdとして受け取ります．このサンプルプログラムではswitch文を使いキー入力の値に応じて分岐させ違う処理をさせています．zが入力されると初期位置のz成分を0.1m増加させます．つまり，zキーを押すたびに直方体全体が上空へ上がっていきます．その下のbreak文は忘れないでください．その他のキーを入力するとdefaultにある&#8221;Input z key&#8221;という文字列がコンソール画面に表示されます．</p>
<p>なお、switch文の変わりにif文でもできますが、キー入力が増え分岐が多くなるとswitch文の方がすっきりした読みやすいプログラムを書けます。</p>
<p><strong>乱　数</strong></p>
<p>ODEとは関係ありませんが乱数も登場します．乱数を使う場合は&#8221;stdlib.h&#8221;をインクルードします．ここではtime()関数も使っているので&#8221;time.h&#8221;もインクルードしています．乱数を使用する場合は、まず，main関数の42行目にあるように乱数を初期化します．そのために<strong>void srand(unsigned seed）</strong>関数を使います。引数seedは乱数を発生させる種を入れます．それが同じ値の場合は，常に同じ乱数系列が発生します．srand(time(NULL))は実行時に乱数の種を変更する一般的な方法です．</p>
<p>実際に乱数を発生させているのがsimLoop関数の30行目のrand関数です．rand関数のプロトタイプ宣言は<strong>int rand(void)</strong>なので引数は取らず，int型の値を返します．RAND_MAXは乱数の最大値なので，30行目は0以上1以下の乱数を発生させ，それを赤成分の値に代入します．従って，表示されている直方体（以下ボックスと表記）の赤成分の色だけが変わることになります．</p>
<p>今回は２つのことを学びました．特に乱数はゲームで使うと非常に面白いゲームになるのでしっかり覚えておきましょう．</p>
<p style="text-align: right;">でむ</p>
<pre class="brush:cpp">/* step3 キー入力　switch文　*/
#include "dm3.h"
#include &lt;time.h&gt;
#include &lt;stdlib.h&gt;

double R[12];  // 回転行列の要素が格納される配列
double p[3] = {0.0, 0.0, 0.05};   // 位置(x,y,z)[m]
double sides[3] = {0.1, 0.1, 0.1}; // 直方体のサイズ(x, y, z)[m]
double start_x = 0.0, start_y = 0.0, start_z = 0.0; // 初期位置

void command(int cmd)
{
    float xyz[3], hpr[3];
    switch (cmd) {
        case 'z':
            start_z += 0.1;
            break;
        default:
            printf("Input z key \n");
    }
}

void simLoop(int pause)        /***  シミュレーションループ　***/
{
  int i, j, num = 11;          // 直方体の数
  static float red = 0.0, green = 0.0, blue = 0.0; // 赤，緑，青成分

  for (i = 0; i &lt; num; i++) {
      for (j = 0; j &lt; num; j++) {
        red = (float) rand()/RAND_MAX;   // 赤成分を乱数で決定
        dsSetColor(red, green, blue);    // 色の設定
        p[0] = start_x;                  // 位置のx成分
        p[1] = i * 0.2 - 1.0  + start_y; // 位置のy成分
        p[2] = j * 0.2 + 0.05 + start_z; // 位置のz成分
        dsDrawBox(p,R,sides); // 直方体の表示
      }
  }
}

int main()         /*** main関数 ***/
{
  srand(time(NULL)); // 乱数の初期化</pre>
<pre class="brush:cpp">
<pre>　// ウインドウの横，縦，シミュレーション関数，コマンド関数
  dmLoop(800, 600, simLoop, command);
　return 0;</pre>
<p>}</pre>
<p><strong>ホームワーク３</strong></p>
<ol>
<li><a href="http://demura.net/wordpress/wp-content/uploads/2010/07/step3-100702b.zip">step3-100702b.zip</a>をダウンロードして実行しよう．</li>
<li>jキーを押すと右，fキーを押すと左にボックス全体が移動するようにしよう．</li>
<li>３行（ｊの値が２）、４列（iの値が３）目のボックスだけをキー操作でx, y, z軸の正負方向へ移動できるようにしよう．つまり，６個のキーを割り当てるなければいけません．simLoop関数の中でif文を使う必要があります．</li>
<li>まず、ボックスを全て白色に変更し，乱数を使い１つのボックスだけ赤色に描画するプログラムを書こう．</li>
<li>[発展問題」　まず、ボックスを全て白にし、９から０までの数字を赤いブロックを複数使いカウントダウン表示しよう。０から９までの数字を表示する部分はそれぞれ関数にすること。</li>
</ol>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=7421&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/7421.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/7421.html" />
	</item>
		<item>
		<title>ODEで学ぶC言語２ [Step2:繰り返し]</title>
		<link>http://demura.net/9ode/7247.html</link>
		<comments>http://demura.net/9ode/7247.html#comments</comments>
		<pubDate>Thu, 10 Jun 2010 23:05:28 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>

		<guid isPermaLink="false">http://demura.net/?p=7247</guid>
		<description><![CDATA[Step1で物体の描画を学びました．今回はNHK大学ロボコンでKITチームが優勝したことを記念して，世界大会の開催地であるエジプトにちなみ，ピラミッドを作ってみましょう．ここでは同じ物体を何個も描画する方法を学びます．
 [...]]]></description>
			<content:encoded><![CDATA[<div id="attachment_4103" class="wp-caption alignnone" style="width: 544px"><a href="http://demura.net/wordpress/wp-content/uploads/2009/06/pyramid1.jpg"><img src="http://demura.net/wordpress/wp-content/uploads/2009/06/pyramid1.jpg" alt="ピラミッド：ホームワークの答え" title="pyramid1" width="534" height="364" /></a><p class="wp-caption-text">ピラミッド：ホームワーク６の答え</p></div>
<p>Step1で物体の描画を学びました．今回はNHK大学ロボコンでKITチームが優勝したことを記念して，世界大会の開催地であるエジプトにちなみ，ピラミッドを作ってみましょう．ここでは同じ物体を何個も描画する方法を学びます．<br />
C言語の繰り返しにはfor文, while文，do while文がありましたね．ここではfor文を使い，図のようなピラミッドを作ってみましょう．では、さっそくソースコードを見ていきます．<br />
<span id="more-7247"></span><br />
13行目のdsSetColor()は色を設定する関数です．引数は光の3原色の値を3個取り，１番目は赤，２番目は緑，３番目は青成分で0以上1以下の値となります．ちなみに，全部0だと黒，全部1.0だと白です．<br />
15から18行目がfor文です．繰り返し回数はnum回，ここでは10行目でnumが11になっているので，11回ループが回ることになります．<br />
16行目のp[1]は絶対座標系のy座標の値です．なお，p[0]にはx座標，p[2]にはz座標の値が入っていて，x座標は地面の中央マーカーから赤マーカーの方向，y座標は中央マーカーから青マーカーの方向，z座標は中央マーカーから上空方向になります．<br />
17行目は直方体の描画です．<br />
これで今回は終わりです．ホームワークは少し難しくします.</p>
<pre class="brush:cpp">/* step2 物体の繰り返し表示　*/
#include "dm2.h"
double R[12];  // 回転行列の各要素が格納される配列
double p[3] = {0.0, 0.0, 0.05};   // 位置(x,y,z)[m]
double sides[3] = {0.1, 0.1, 0.1}; // 直方体のサイズ(x, y, z)[m]

void simLoop(int pause)        /***  シミュレーションループ　***/
{
　int i, num = 11;             // 直方体の数
　dsSetColor(1.0, 0.0, 0.0);   // 赤色の設定(赤，緑，青）
　for (i = 0; i &lt; num; i++) {
　　p[1] = i * 0.2;
　　dsDrawBox(p,R,sides); // 直方体の表示
　}
}

int main()         /*** main関数 ***/
{
　dmLoop(800, 600, simLoop); // シミュレーションループ ウインドウの幅，高，ループ関数
　return 0;
}</pre>
<p><strong>ホームワーク２</strong></p>
<ol>
<li><a href="http://demura.net/wordpress/wp-content/uploads/2010/06/step2-100611.zip">step2-100611.zip</a>をダウンロードして実行しよう．</li>
<li>赤い直方体の色を黄に変えよう．</li>
<li>赤い直方体の位置を左にずらし，中央の直方体が原点に来るようにしましょう．</li>
<li>上の問題で，直方体の色を全て違う色にしょう．</li>
<li>forループを２重にし，ｘ軸方向にも直方体を描画し，合計121個の直方体を表示しよう．</li>
<li>forループを３重にし，z軸方向にも直方体を描画し，直方体の間隔も調整して上図のようなピラミッドを作ろう．</li>
</ol>
<p>昔エジプトに行きピラミッドに少しだけ登ったことがあります。遠くからはきれいな四角錐に見えますが、大きな立方体が積み重ねられできています。残念ながら今は登ることが禁止されているようですね。</p>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=7247&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/7247.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/7247.html" />
	</item>
		<item>
		<title>ODEで学ぶC言語２ [Step1:物体の描画]</title>
		<link>http://demura.net/9ode/7199.html</link>
		<comments>http://demura.net/9ode/7199.html#comments</comments>
		<pubDate>Thu, 03 Jun 2010 23:25:08 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>

		<guid isPermaLink="false">http://demura.net/?p=7199</guid>
		<description><![CDATA[講義でC言語を教えているのですが，最近のリアルなゲームに慣れた学生にはテキストベースのプログラムではあまりモチベーションが上がらないようです．そこで，昨年に引き続き，ODEを使いC言語を初めて学ぶための連載「ODEで学ぶ [...]]]></description>
			<content:encoded><![CDATA[<div id="attachment_4039" class="wp-caption alignnone" style="width: 411px"><a href="http://demura.net/wordpress/wp-content/uploads/2009/06/step1.jpg"><img src="http://demura.net/wordpress/wp-content/uploads/2009/06/step1.jpg" alt="step1.cppの実行画面" title="step1" width="401" height="300" class="size-full wp-image-4039" /></a><p class="wp-caption-text">step1.cppの実行画面</p></div>
<p>講義でC言語を教えているのですが，最近のリアルなゲームに慣れた学生にはテキストベースのプログラムではあまりモチベーションが上がらないようです．そこで，昨年に引き続き，ODEを使いC言語を初めて学ぶための連載「ODEで学ぶC言語2」を始めます．昨年この方法で学生に教え，反応がまずまずでした．一部分かりづらいところがあったので，今年はさらなるわかりやすさを目指していきたいと思います．</p>
<p>なお，講義では別の教科書で一通りC言語を教えたので，プログラミング能力を高めるための演習ベースになり，C言語に対する細かい説明はあまりしません．プログラミングの楽しい演習だと思ってください．<br />
<span id="more-7199"></span></p>
<p>今回は何もなかった仮想空間に物体を表示させてみましょう．ODEではいろいろな形状がサポートされています．ここではその中でも使い方が最も簡単な球を表示させます．</p>
<pre class="brush:cpp;">/* step1 球の表示　*/
#include "dm1.h"

double R[12];                  // 回転行列(姿勢)の値を入れる配列
double p[3] = {0.0, 0.0, 1.0}; // 位置(x,y,z)[m]
double r = 0.2;                // 半径 [m]

void simLoop(int pause)        /***  シミュレーションループ　***/
{
  dsDrawSphere(p,R,r);         // 球の描画
}

int main()         /*** main関数 ***/
{
  dmLoop(800, 600, simLoop); // シミュレーションループ（ウインドウの横，縦）
  return 0;
}</pre>
<p>物体を３次元空間上に表示させるためには，物体の位置と姿勢を決める必要があります．ODEでは姿勢を回転行列とよばれる行列で表しています．その行列の要素を格納するのが配列R[12]です．なお，位置は要素数３個のdouble型の配列p[3]に格納しています．なお，R[12]には謎のヘッダファイルdm1.hの中で単位行列が設定されています．</p>
<p>位置のx座標(手前方向）を表す変数pの1番目の要素p[0]には0.0[m]，y座標（右方向）, z座標（高さ方向）を表すp[1], p[2]には0.0[m],　1.0[m]が設定されています．座標系は右手系です。ODEでは単位系はSI単位系を考えます．長さはm，質量はkg，力はNとなります．</p>
<p>ソースコードのなかほどにあるsimLoop関数にシミュレーションでやりたいことを書きます．ここでは，球を表示したいのでdsDrawSphere関数を使って，位置p，姿勢R, 半径rの球を描画しています．なお、このソースコードだけではわかりませんが、simLoop関数はdmLoop関数の中で毎回呼び出されています。</p>
<p>今回はこれで終わりです．また，また簡単でしたね．</p>
<ul>
<li><strong>ホームワーク１</strong>
<ol>
<li><a href="http://demura.net/wordpress/wp-content/uploads/2010/06/step1-100604.zip">step1-100604</a>をダウンロードし，実行してください．</li>
<li>手順
<ul>
<li>ode-0.11.1がインストールされていなかったら<a href="http://demura.net/9ode/3850.html">この説明に従いインストールする</a>．</li>
<li>ダウンロードしたファイルをc:\ode-0.11.1\myprogの中に保存する．</li>
<li>そこで解凍する．c:\ode-0.11.1\myprog\step1というフォルダが作られます．</li>
<li>c:\ode-0.11.1\myprog\step1\step1.cbpをダブルクリックしてcodeblocksを起動しビルド・実行する．<strong>ダブルクリックするファイルの拡張子はcbpです．間違ってcppをダブルクリックしないように！</strong></li>
</ul>
<li>球の位置と大きさを変更してみましょう．</li>
<li>直方体を表示させてください．次の関数を使います．</li>
<ul>
<li>void dsDrawBox(const double　p[3], const double R[12], const double sides[3])</li>
<li>上は関数のプロトタイプ宣言の形式なので，呼び出すときはconst doubleなどの型名を入れてはいけません．引数が配列の場合は，サンプルプログラムのように配列名だけを入れてください．</li>
<li>1, 2番目の引数はdsDrawSphereのときと同じです．3番目の引数は直方体のx,y,z方向のサイズ[m]が入っている要素数3個の配列です．位置を表す配列pと同じように初期化すれば大丈夫です．なお, doubleの前にあるconstは値を変えてはいけないという意味です。円柱を表示させてください</li>
</ul>
<li>円柱を表示させましょう．</li>
<ul>
<li>void dsDrawCylinder(const double　p[3], const double R[12],  float l, float r );</li>
<li>ここで，lは長さ，rは半径です．</li>
</ul>
</li>
<li>カプセルを表示させてください．
<ul>
<li>void dsDrawCapsule(const double　p[3], const double R[12], float l,  float r );</li>
</ul>
</li>
</ol>
</li>
</ul>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=7199&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/7199.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/7199.html" />
	</item>
		<item>
		<title>ロボット情報学ハンドブック発売</title>
		<link>http://demura.net/9ode/6603.html</link>
		<comments>http://demura.net/9ode/6603.html#comments</comments>
		<pubDate>Thu, 18 Mar 2010 12:13:00 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>

		<guid isPermaLink="false">http://demura.net/?p=6603</guid>
		<description><![CDATA[
ロボット情報学ハンドブックが発売になりました．値段はさておき，情報学とロボット工学にまたがる新領域をターゲットとしたハンドブックはおそらく世界初ではないでしょうか？　これからの知能ロボットは情報学抜きでは考えることがで [...]]]></description>
			<content:encoded><![CDATA[<p><iframe src="http://rcm-jp.amazon.co.jp/e/cm?lt1=_blank&#038;bc1=000000&#038;IS2=1&#038;npa=1&#038;bg1=FFFFFF&#038;fc1=000000&#038;lc1=0000FF&#038;t=demuranet-22&#038;o=9&#038;p=8&#038;l=as1&#038;m=amazon&#038;f=ifr&#038;asins=4764955075" style="width:120px;height:240px;" scrolling="no" marginwidth="0" marginheight="0" frameborder="0"></iframe></p>
<p>ロボット情報学ハンドブックが発売になりました．値段はさておき，情報学とロボット工学にまたがる新領域をターゲットとしたハンドブックはおそらく世界初ではないでしょうか？　これからの知能ロボットは情報学抜きでは考えることができません．ロボカップやつくばチャレンジでもその傾向が顕著になりつつあります．<br />
<span id="more-6603"></span></p>
<p>国内外の研究者１３５名が各項目を担当しており，私もODEの項を担当させて頂きました．本を執筆すると通常は献本がもらえるのですが，執筆者が多いためか割引価格で購入するようになっています．</p>
<p>とてもポケットマネーで購入する金額ではないので，２０１０年度に研究費で購入することになるでしょう．大学の管財をとおして著者割引で購入できるか謎です．</p>
<p>でむ</p>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=6603&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/6603.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/6603.html" />
	</item>
		<item>
		<title>ＯＤＥ本の韓国語版ができたわけ</title>
		<link>http://demura.net/9ode/6595.html</link>
		<comments>http://demura.net/9ode/6595.html#comments</comments>
		<pubDate>Tue, 16 Mar 2010 23:46:01 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>
		<category><![CDATA[ODE本]]></category>

		<guid isPermaLink="false">http://demura.net/?p=6595</guid>
		<description><![CDATA[拙著ODE本の韓国語版ができた理由を訳者の金先生に聞きました．

韓国の出版社が日本で売れ筋の本を調べた結果，拙著が選ばれたとのことです．また，訳者は日本で学位を取得している韓国人のロボット研究者から選らば得れたというこ [...]]]></description>
			<content:encoded><![CDATA[<p>拙著ODE本の韓国語版ができた理由を訳者の金先生に聞きました．</p>
<p><span id="more-6595"></span></p>
<p>韓国の出版社が日本で売れ筋の本を調べた結果，拙著が選ばれたとのことです．また，訳者は日本で学位を取得している韓国人のロボット研究者から選らば得れたということでした．</p>
<p>既に２度訳者の校正が終わっているので，4月中には発刊される予定です．</p>
<p style="text-align: right;">でむ</p>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=6595&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/6595.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/6595.html" />
	</item>
		<item>
		<title>ＯＤＥ本の韓国語訳４月頃発売</title>
		<link>http://demura.net/9ode/6581.html</link>
		<comments>http://demura.net/9ode/6581.html#comments</comments>
		<pubDate>Fri, 12 Mar 2010 07:59:22 +0000</pubDate>
		<dc:creator>demu</dc:creator>
				<category><![CDATA[ODE]]></category>
		<category><![CDATA[ODE本]]></category>

		<guid isPermaLink="false">http://demura.net/?p=6581</guid>
		<description><![CDATA[拙著ODE本「ロボットシミュレーション-Open Dynamics Engineによるロボットプログラミング- 森北出版」の韓国語版が、２０１０年４月頃発売されるそうです．
訳者の韓国中央大学金先生から連絡がありました． [...]]]></description>
			<content:encoded><![CDATA[<p>拙著ODE本「<a href="http://www.morikita.co.jp/shoshi/ISBN978-4-627-84691-3.html">ロボットシミュレーション-Open Dynamics Engineによるロボットプログラミング- 森北出版</a>」の韓国語版が、２０１０年４月頃発売されるそうです．</p>
<p>訳者の韓国中央大学金先生から連絡がありました．韓国語版でも１冊の売上につき１ドルをThe ODE Projectに寄付してもらうようにしていますので，多く売上のあることを願っています．</p>
<p style="text-align: right;">でむ</p>
<img src="http://demura.net/wordpress/?ak_action=api_record_view&id=6581&type=feed" alt="" />]]></content:encoded>
			<wfw:commentRss>http://demura.net/9ode/6581.html/feed</wfw:commentRss>
		<slash:comments>0</slash:comments>
	<xhtml:link rel="alternate" media="handheld" type="text/html" href="http://demura.net/9ode/6581.html" />
	</item>
	</channel>
</rss>
